Skip to content

Commit 54487cc

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 94301f5 commit 54487cc

File tree

2 files changed

+5
-2
lines changed

2 files changed

+5
-2
lines changed

ArduPlane/Attitude.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -659,8 +659,11 @@ void Plane::update_load_factor(void)
659659
}
660660
#endif
661661

662-
float max_load_factor = sq(smoothed_airspeed / MAX(aparm.airspeed_min, 1));
662+
float airspeed_stall = is_positive(aparm.airspeed_stall)
663+
? aparm.airspeed_stall
664+
: aparm.airspeed_min;
663665

666+
float max_load_factor = sq(smoothed_airspeed / MAX(airspeed_stall, 1));
664667
if (max_load_factor <= 1) {
665668
// our airspeed is below the minimum airspeed. Limit roll to
666669
// 25 degrees

ArduPlane/Parameters.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -323,7 +323,7 @@ const AP_Param::Info Plane::var_info[] = {
323323

324324
// @Param: AIRSPEED_STALL
325325
// @DisplayName: Stall airspeed
326-
// @Description: If stall prevention is enabled this speed is used to calculate the minimum airspeed while banking. If this is set to 0 then the stall speed is assumed to be the minimum airspeed speed. Typically set slightly higher then true stall speed. Value is as an indicated (calibrated/apparent) airspeed.
326+
// @Description: If stall prevention is enabled this speed is used for its calculations. If set to 0 then AIRSPEED_MIN is used instead. Typically set slightly higher than the true stall speed. Value is as an indicated (calibrated/apparent) airspeed.
327327
// @Units: m/s
328328
// @Range: 5 75
329329
// @User: Standard

0 commit comments

Comments
 (0)