-
Notifications
You must be signed in to change notification settings - Fork 18k
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
Attitude stall prevention adjustments #29092
base: master
Are you sure you want to change the base?
Attitude stall prevention adjustments #29092
Conversation
3003cd6
to
86a36b2
Compare
There is some pre-existing work here that we never did merge, but I think your proposed fix is similar. #24320 #24509 Re the second commit, I think swapping stall to speed if set is fine. Less keen on the 0.85 scale factor on airspeed min, the vast majority have no idea what there stall speed is, so we need to be conservative. I think if you do make that change you would need to remove the correction that is done in TECS here because the load factor would be lower already: ardupilot/libraries/AP_TECS/AP_TECS.cpp Line 418 in 25e1701
|
86a36b2
to
fce1d86
Compare
Thank you for linking that because I hadn't noticed that the load factor formula itself was also wrong. I have removed the scaling of the min speed to get the stall speed, so now the second commit is just using the stall speed if set to get less restrictive roll limits. |
In general when there the pitch and roll exist the formula for the aerodynamic load factor should be as follows: aerodynamic_load_factor = cosf(radians(_ahrs.pitch))/cosf(radians(demanded_roll)); which in case of turns (in the horizontal plane) becomes aerodynamic_load_factor = 1.0f/cosf(radians(demanded_roll)); formulas can be obtained from equations of balanced spiral: liftForce * cos(roll) = gravityForce * cos(pitch); liftForce * sin(roll) = gravityForce * lateralAcceleration / gravityAcceleration; // as mass = gravityForce/gravityAcceleration see issue ArduPilot#24320 [ArduPilot#24320]. To connect loadFactor to airspeed we can use formula of balancing between lift force and gravity force: liftForce = loadFactor * gravityForce; on the other hand lift force can be expressed as liftForce = 0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea; minimum airseepd is at loadFactor = 1 and lift force only balances the gravit force, so gravity force (which is same as lift force at minimum airspeed) with minimum airspeed can be expressed as gravityForce = 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea; substituting gravit force in previous formula gives us 0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea = loadFactor * 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea; from where we get: loadFactor = sq(airspeed / airspeed_min); These changes also require changes in ardupilot/libraries/AP_TECS/AP_TECS.cpp Line 418 (according to the comments by Peter Hall): _TASmin *= _load_factor; should be changed to _TASmin *= safe_sqrt(_load_factor); See details here: ArduPilot#24320
…r the load factor To connect loadFactor to airspeed we can use formula of balancing between lift force and gravity force: liftForce = loadFactor * gravityForce; on the other hand lift force can be expressed as liftForce = 0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea; minimum airseepd is at loadFactor = 1 and lift force only balances the gravit force, so gravity force (which is same as lift force at minimum airspeed) with minimum airspeed can be expressed as gravityForce = 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea; substituting gravit force in previous formula gives us 0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea = loadFactor * 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea; from where we get: loadFactor = sq(airspeed / airspeed_min); and_TASmin should be _TASmin *= safe_sqrt(_load_factor);
I felt bad we had overlooked that original PR for so long so I have rebased it here: #29101 Do you agree with all the changes there? Once that is in you could rebase this to bring in the use of the stall speed param. |
I agree that's the right thing to do
Sounds good! |
fce1d86
to
4167ec1
Compare
4167ec1
to
54487cc
Compare
The new AIRSPEED_STALL parameter wasn't being used for the roll stall prevention, and no adjustment for bank angle was being made. This led to a slight under-limiting of bank angle. Fixed both issues by using the stall airspeed from the TECS, to avoid repeating the same logic, and adjusted the description of the AIRSPEED_STALL parameter accordingly. This improves consistency as it uses AIRSPEED_STALL for all stall prevention calculations where it applies, and sets up AIRSPEED_STALL to become a key parameter in further stall prevention improvements.
54487cc
to
75fb2c8
Compare
@IamPete1 What do you think about this now? It centralizes the stall speed in the TECS, which means that this load factor routine and other future stall prevention logic can easily reference a roll-compensated stall speed that is based on either AIRSPEED_MIN of AIRSPEED_STALL if set. I'm adding pitch stall prevention on top of this so I think it makes sense. Also, maybe the _TASmin member in the TECS should be renamed to _TASstall, as that's what it's treated as in the formulas. |
// Return stall airspeed, adjusted for bank angle. This is based on | ||
// AIRSPEED_MIN as a very conservative estimate if AIRSPEED_STALL is not | ||
// set. | ||
float get_stall_airspeed(void) const { | ||
return _TASmin / _ahrs.get_EAS2TAS(); | ||
} | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'm not a fan of calling this the stall airspeed. AIRSPEED_MIN
is explicitly meant to NOT be the stall airspeed, as per its parameter definition.
As a side-note, the resulting maximum loading factor is the maximum allowed loading factor, not the maximum loading factor supported by the airframe. That is what would correspond to the stall airspeed.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I understand, but if AIRSPEED_STALL is defined, this is going to be much closer to the actual stall speed. Since the idea behind AIRSPEED_STALL is to optionally allow for maneuvers that are closer to the stall speed, and the related math (the maximum loading factor and the scaling with bank angle) is canonically done based on Vstall, we're indeed considering AIRSPEED_MIN to be the stall airspeed in the code as it stands. And I was embracing that here because it's something that makes sense from a safety perspective and considering how poorly most AP aircraft are tuned. It makes a lot of sense to consider the minimum navigation speed (AIRSPEED_MIN) to be the stall speed in the TECS code unless the user explicitly defines an actual stall speed because that works out perfectly for both plug and play and more advanced users.
As a side-note, the resulting maximum loading factor is the maximum allowed loading factor, not the maximum loading factor supported by the airframe. That is what would correspond to the stall airspeed.
But the min. airspeed increase based on bank angle isn't something that makes any sense for an airspeed that isn't a stall speed.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@rubenp02 I think you're onto something.
But first, some clarifications.
Currently, this is what happens (to my understanding):
Attitude.cpp::update_load_factor()
will calculate a load factor usingAIRSPEED_MIN
.- It will then communicate a load factor to TECS.
- In turn, TECS will increase
_TASmin
(its minimum airspeed limit) by: AIRSPEED_MIN*_load_factor
- (or if defined)
max(
AIRSPEED_MIN, AIRSPEED_STALL*_load_factor)`.
If I read your code correctly, you want to take the final TECS::_TASmin
and feed it back into update_load_factor()
.
Won't this create a feedback loop, constantly increasing _TASmin
?
I don't think that's right.
I think you have some more errors in your logic:
Since the idea behind AIRSPEED_STALL is to optionally allow for maneuvers that are closer to the stall speed
This is not correct. The idea is the allow maneuvers at AIRSPEED_MIN
, as introduced here.
But the min. airspeed increase based on bank angle isn't something that makes any sense for an airspeed that isn't a stall speed.
Indeed. And as far as I understand, the PR linked above fixed that.
However, I think I see the merit in your idea.
Are you proposing switching the load factor calculation based on AIRSPEED_STALL
, when that's available?
If yes, I think it's fine to repeat a similar if (is_positive(aparm.airspeed_stall))
structure in update_load_factor()
.
And I understand that will have the effect of not exaggerating the load factor.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Currently, this is what happens (to my understanding):
- Attitude.cpp::update_load_factor() will calculate a load factor using AIRSPEED_MIN.
- It will then communicate a load factor to TECS.
- In turn, TECS will increase _TASmin (its minimum airspeed limit) by:
- AIRSPEED_MIN*_load_factor
- (or if defined) max(AIRSPEED_MIN, AIRSPEED_STALL*_load_factor)`.
If I read your code correctly, you want to take the final TECS::_TASmin and feed it back into update_load_factor().
Won't this create a feedback loop, constantly increasing _TASmin?
I don't think that's right.
Take this with a grain of salt as I'm still learning the codebase, but I don't think that's true. The load factor is based on the demanded roll so it's entirely independent from the airspeed and thus no feedback loop is possible. To put it a different way, in TECS we're essentially doing:
true_airspeed_min_or_stall = true_airspeed_min_or_stall * sqrt(1 / cos(demanded_roll))
And in the attitude controller:
roll_limit = acos(1 / (current_airspeed / airspeed_min_or_stall)^2)
One side is adjusting the min. speed and the other the max. roll, so they don't interfere with each other.
Since the idea behind AIRSPEED_STALL is to optionally allow for maneuvers that are closer to the stall speed
This is not correct. The idea is the allow maneuvers at AIRSPEED_MIN, as introduced here.
As I understand it, it does do what I said even if that wasn't the intention, and it seems quite useful. If AIRSPEED_STALL is unset it does exactly what it did before that param. existed, and if it's set, it uses it in AIRSPEED_MIN's place. Since _STALL is lower than _MIN, _TASmin will end up being less conservative. This exact behaviour is one of the things this PR attempts to apply to the roll stall prevention, based on the same AIRSPEED_STALL parameter.
But the min. airspeed increase based on bank angle isn't something that makes any sense for an airspeed that isn't a stall speed.
Indeed. And as far as I understand, the PR linked above fixed that.
But the AIRSPEED_MIN still gets compensated for bank angle if AIRSPEED_STALL isn't set.
Ultimately where I want to go with this is to have a single source of truth regarding the stall speed as far as AP is concerned (i.e. as conservative or as precise as the user has configured it). This will be very useful to improve the stall prevention functionality, and to avoid future mistakes (this part of the code was riddled with uncanonical formulas and inconsistencies when it came to compensating for bank angle).
Attitude stall prevention adjustments
Description
TECS: Add getter for bank-adjusted stall airspeed.
Plane: Use stall speed for roll stall prevention:
The new AIRSPEED_STALL parameter wasn't being used for the roll stall prevention, and no adjustment for bank angle was being made. This led to a slight under-limiting of bank angle.
Fixed both issues by using the stall airspeed from the TECS, to avoid repeating the same logic, and adjusted the description of the AIRSPEED_STALL parameter accordingly. This improves consistency as it uses AIRSPEED_STALL for all stall prevention calculations where it applies, and sets up AIRSPEED_STALL to become a key parameter in further stall prevention improvements.
This PR is branched from #29101