Skip to content

ArduPlane: Fixed formulas for load factor and roll, also corrected _TASmin in AP_TECS accordingly #24509

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

Open
wants to merge 4 commits into
base: master
Choose a base branch
from
Open
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
11 changes: 7 additions & 4 deletions ArduPlane/Attitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -607,7 +607,8 @@ void Plane::update_load_factor(void)
// limit to 85 degrees to prevent numerical errors
demanded_roll = 85;
}
aerodynamic_load_factor = 1.0f / safe_sqrt(cosf(radians(demanded_roll)));
// loadFactor = liftForce / gravityForce, where gravityForce = liftForce * cos(roll) on balanced horizontal turn
aerodynamic_load_factor = 1.0f / cosf(radians(demanded_roll));

#if HAL_QUADPLANE_ENABLED
if (quadplane.available() && quadplane.transition->set_FW_roll_limit(roll_limit_cd)) {
Expand All @@ -630,8 +631,9 @@ void Plane::update_load_factor(void)
return;
}
#endif

float max_load_factor = smoothed_airspeed / MAX(aparm.airspeed_min, 1);

float max_load_factor = sq(smoothed_airspeed / MAX(aparm.airspeed_min, 1));

if (max_load_factor <= 1) {
// our airspeed is below the minimum airspeed. Limit roll to
// 25 degrees
Expand All @@ -644,7 +646,8 @@ void Plane::update_load_factor(void)
// allow at least 25 degrees of roll however, to ensure the
// aircraft can be maneuvered with a bad airspeed estimate. At
// 25 degrees the load factor is 1.1 (10%)
int32_t roll_limit = degrees(acosf(sq(1.0f / max_load_factor)))*100;

int32_t roll_limit = degrees(acosf(1.0f / max_load_factor))*100;
if (roll_limit < 2500) {
roll_limit = 2500;
}
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -415,7 +415,8 @@ void AP_TECS::_update_speed(float DT)
if (aparm.stall_prevention) {
// when stall prevention is active we raise the minimum
// airspeed based on aerodynamic load factor
_TASmin *= _load_factor;

_TASmin *= safe_sqrt(_load_factor);
}

if (_TASmax < _TASmin) {
Expand Down