Skip to content

Commit 86a36b2

Browse files
committed
Plane: Use AIRSPEED_STALL for roll stall prevent.
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.
1 parent 3c80a8d commit 86a36b2

File tree

1 file changed

+7
-1
lines changed

1 file changed

+7
-1
lines changed

ArduPlane/Attitude.cpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -657,7 +657,13 @@ void Plane::update_load_factor(void)
657657
}
658658
#endif
659659

660-
float max_load_factor = sq(smoothed_airspeed / MAX(aparm.airspeed_min, 1));
660+
float airspeed_stall = is_positive(aparm.airspeed_stall)
661+
? aparm.airspeed_stall
662+
// Per the param. description, AIRSPEED_MIN should be 20% higher than
663+
// the stall speed. Use 15% less to be on the safe side.
664+
: aparm.airspeed_min * 0.85;
665+
666+
float max_load_factor = sq(smoothed_airspeed / MAX(airspeed_stall, 1));
661667
if (max_load_factor <= 1) {
662668
// our airspeed is below the minimum airspeed. Limit roll to
663669
// 25 degrees

0 commit comments

Comments
 (0)