Skip to content
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

Open
wants to merge 4 commits into
base: master
Choose a base branch
from

Conversation

rubenp02
Copy link
Contributor

@rubenp02 rubenp02 commented Jan 16, 2025

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

@rubenp02 rubenp02 force-pushed the feature/attitude-stall-prevention-adjustments branch from 3003cd6 to 86a36b2 Compare January 16, 2025 14:57
@IamPete1
Copy link
Member

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:

_TASmin = MAX(_TASmin, aparm.airspeed_stall*EAS2TAS*_load_factor);

@rubenp02 rubenp02 marked this pull request as draft January 16, 2025 22:24
@rubenp02 rubenp02 force-pushed the feature/attitude-stall-prevention-adjustments branch from 86a36b2 to fce1d86 Compare January 17, 2025 17:27
@rubenp02 rubenp02 marked this pull request as ready for review January 17, 2025 17:31
@rubenp02
Copy link
Contributor Author

rubenp02 commented Jan 17, 2025

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);
@IamPete1
Copy link
Member

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.

@rubenp02
Copy link
Contributor Author

I agree that's the right thing to do

Once that is in you could rebase this to bring in the use of the stall speed param.

Sounds good!

@rubenp02 rubenp02 force-pushed the feature/attitude-stall-prevention-adjustments branch from fce1d86 to 4167ec1 Compare January 20, 2025 09:46
@rubenp02 rubenp02 changed the title Attitude stall prevention adjustments Use AIRSPEED_STALL for roll stall prevention if available Jan 20, 2025
@rubenp02 rubenp02 force-pushed the feature/attitude-stall-prevention-adjustments branch from 4167ec1 to 54487cc Compare January 20, 2025 11:17
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.
@rubenp02 rubenp02 force-pushed the feature/attitude-stall-prevention-adjustments branch from 54487cc to 75fb2c8 Compare January 20, 2025 16:01
@rubenp02 rubenp02 changed the title Use AIRSPEED_STALL for roll stall prevention if available Attitude stall prevention adjustments Jan 20, 2025
@rubenp02
Copy link
Contributor Author

@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.

Comment on lines +80 to +86
// 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();
}

Copy link
Contributor

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.

Copy link
Contributor Author

@rubenp02 rubenp02 Jan 21, 2025

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.

Copy link
Contributor

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):

  1. Attitude.cpp::update_load_factor() will calculate a load factor using AIRSPEED_MIN.
  2. It will then communicate a load factor to TECS.
  3. In turn, TECS will increase _TASmin (its minimum airspeed limit) by:
  4. AIRSPEED_MIN*_load_factor
  5. (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.

Copy link
Contributor Author

@rubenp02 rubenp02 Jan 21, 2025

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):

  1. Attitude.cpp::update_load_factor() will calculate a load factor using AIRSPEED_MIN.
  2. It will then communicate a load factor to TECS.
  3. In turn, TECS will increase _TASmin (its minimum airspeed limit) by:
  4. AIRSPEED_MIN*_load_factor
  5. (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).

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Jan 21, 2025
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants