Skip to content

Commit fce1d86

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.
1 parent 9af03df commit fce1d86

File tree

1 file changed

+5
-1
lines changed

1 file changed

+5
-1
lines changed

ArduPlane/Attitude.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -657,7 +657,11 @@ 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+
: aparm.airspeed_min;
663+
664+
float max_load_factor = sq(smoothed_airspeed / MAX(airspeed_stall, 1));
661665
if (max_load_factor <= 1) {
662666
// our airspeed is below the minimum airspeed. Limit roll to
663667
// 25 degrees

0 commit comments

Comments
 (0)