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.
  • Loading branch information
rubenp02 committed Jan 20, 2025
1 parent 94301f5 commit 54487cc
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 2 deletions.
5 changes: 4 additions & 1 deletion ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -659,8 +659,11 @@ void Plane::update_load_factor(void)
}
#endif

float max_load_factor = sq(smoothed_airspeed / MAX(aparm.airspeed_min, 1));
float airspeed_stall = is_positive(aparm.airspeed_stall)
? aparm.airspeed_stall
: aparm.airspeed_min;

float max_load_factor = sq(smoothed_airspeed / MAX(airspeed_stall, 1));
if (max_load_factor <= 1) {
// our airspeed is below the minimum airspeed. Limit roll to
// 25 degrees
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,7 +323,7 @@ const AP_Param::Info Plane::var_info[] = {

// @Param: AIRSPEED_STALL
// @DisplayName: Stall airspeed
// @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.
// @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.
// @Units: m/s
// @Range: 5 75
// @User: Standard
Expand Down

0 comments on commit 54487cc

Please sign in to comment.