We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent 9af03df commit fce1d86Copy full SHA for fce1d86
ArduPlane/Attitude.cpp
@@ -657,7 +657,11 @@ void Plane::update_load_factor(void)
657
}
658
#endif
659
660
- float max_load_factor = sq(smoothed_airspeed / MAX(aparm.airspeed_min, 1));
+ 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));
665
if (max_load_factor <= 1) {
666
// our airspeed is below the minimum airspeed. Limit roll to
667
// 25 degrees
0 commit comments