Skip to content

Plane: Attitude stall prevention adjustments #29092

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 7 additions & 2 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -659,7 +659,12 @@ void Plane::update_load_factor(void)
}
#endif

float max_load_factor = sq(smoothed_airspeed / MAX(aparm.airspeed_min, 1));
float stall_airspeed_1g = is_positive(aparm.airspeed_stall)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
float stall_airspeed_1g = is_positive(aparm.airspeed_stall)
const float stall_airspeed_1g = is_positive(aparm.airspeed_stall)

? aparm.airspeed_stall
: aparm.airspeed_min;

float max_load_factor =
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
float max_load_factor =
const float max_load_factor =

sq(smoothed_airspeed / MAX(stall_airspeed_1g, 1));

if (max_load_factor <= 1) {
// our airspeed is below the minimum airspeed. Limit roll to
Expand All @@ -671,7 +676,7 @@ void Plane::update_load_factor(void)
// load limit. Limit our roll to a bank angle that will keep
// the load within what the airframe can handle. We always
// allow at least 25 degrees of roll however, to ensure the
// aircraft can be manoeuvred with a bad airspeed estimate. At
// aircraft can be manoeuvered with a bad airspeed estimate. At
// 25 degrees the load factor is 1.1 (10%)
int32_t roll_limit = degrees(acosf(1.0f / max_load_factor))*100;
if (roll_limit < 2500) {
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
Loading