Skip to content

Commit

Permalink
Plane: Use AIRSPEED_STALL for roll stall prevent.
Browse files Browse the repository at this point in the history
Similarly to how it's done in the TECS stall prevention, used
AIRSPEED_STALL (if available) in the stall prevention calculations.
Otherwise use a safe approximation based on AIRSPEED_MIN.
  • Loading branch information
rubenp02 committed Jan 16, 2025
1 parent 3c80a8d commit 3003cd6
Showing 1 changed file with 7 additions and 1 deletion.
8 changes: 7 additions & 1 deletion ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -657,7 +657,13 @@ void Plane::update_load_factor(void)
}
#endif

float max_load_factor = sq(smoothed_airspeed / MAX(aparm.airspeed_min, 1));
_TASstall = is_positive(aparm.airspeed_stall)
? aparm.airspeed_stall
// Per the param. description, AIRSPEED_MIN should be 20% higher
// than the stall speed. Use 15% less to be on the safe side.
: aparm.airspeed_min * 0.85;

float max_load_factor = sq(smoothed_airspeed / MAX(_TASstall, 1));
if (max_load_factor <= 1) {
// our airspeed is below the minimum airspeed. Limit roll to
// 25 degrees
Expand Down

0 comments on commit 3003cd6

Please sign in to comment.