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

AP_TECS: Add a separate stall speed parameter used for minimum speed scaling #27442

Merged
merged 3 commits into from
Jul 23, 2024

Conversation

WickedShell
Copy link
Contributor

When stall prevention is enabled we were scaling from the aircraft's minimum flight speed. However this is normally already picked as being above the stall speed, and for a variety of reasons we may want to pin the aircraft at a higher minimum speed. But if the aircraft was commanded to fly to close to that minimum speed as soon as it banked for a pattern it would command a increase in speed to keep it away from stalling. However if your minimum speed is far from stalling this increase was incorrect. To make it worse what this actually results in happening is an aircraft diving for more speed (over 10 m/s on some aircraft) as well as descending to gain that speed resulting in over 200 foot deviations in altitude control.

This was found on a real vehicle (in a rather alarming flight), I've recreated the behavior in the sim easily, and tested the patch in the sim. The one question I have is do we want to keep this parameter within TECS which is the only user currently, or should it be moved into the vehicle side just incase we want to do more with it in the future?

If the stall speed isn't configured this will result in no change in behavior.

@timtuxworth
Copy link
Contributor

This seems like a very good idea to me.

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Jul 5, 2024
@CraigElder CraigElder changed the title AP_TECS: Add a seperate stall speed parameter used for minimum speed scaling AP_TECS: Add a separate stall speed parameter used for minimum speed scaling Jul 9, 2024
// @Units: m/s
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("STALL_SPEED", 34, AP_TECS, _stall_speed, 0),
Copy link
Contributor

Choose a reason for hiding this comment

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

nice find!
needs to be an EAS not a TAS to be consistent with other airspeed params, ideally it would be AIRSPEED_STALL and go along with AIRSPEEED_CRUISE etc
also, stall prevention (limiting bank) happens when TECS is not running, so should not be in TECS

Copy link
Contributor Author

Choose a reason for hiding this comment

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

It is in EAS. When I use it, I multiply by EAS2TAS.

Okay, happy to move where the parameter lives. That is sort of the thought I was having, I only stuck it here as that's what was using it.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Param moved, and retested in SITL.

@WickedShell WickedShell force-pushed the wickedshell/tecs-stall-speed branch from dec5c40 to e78a850 Compare July 9, 2024 16:31
When stall prevention is enabled we were scaling from the aircraft's
minimum flight speed. However this is normally already picked as being
above the stall speed, and for a variety of reasons we may want to pin
the aircraft at a higher minimum speed. But if the aircraft was
commanded to fly to close to that minimum speed as soon as it banked for
a pattern it would command a increase in speed to keep it away from
stalling. However if your minimum speed is far from stalling this
increase was incorrect. To make it worse what this actually results in
happening is an aircraft diving for more speed (over 10 m/s on some
aircraft) as well as descending to gain that speed resulting in over 200
foot deviations in altitude control.
@WickedShell WickedShell force-pushed the wickedshell/tecs-stall-speed branch from 37ed795 to a725934 Compare July 9, 2024 16:55
@WickedShell
Copy link
Contributor Author

WickedShell commented Jul 9, 2024

As a comment here, adding it to the stall prevention code in ArduPlane/Attitude.cpp seems like a trivial change, but it results in a new problem (doesn't compute max load appropriately on the high side, which probably should not have been calculated from the stall speed in the first place). I'm working through how we should change that at the moment, but I'd like to bring that in as a separate follow up.

Still working through it, but the idea here is normally encapsulated in a Vg diagram (ie https://www.faatest.com/books/FLT/Chapter17/Vg%20Diagram_files/imageTHE.jpg ) notice that in that diagram stall speed is 62 mph (1G load), but can handle 2G load at 92 mph. The current code assumes you need 2x the stall speed to handle a 2G load.

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

LGTM

@tridge tridge merged commit edaddc0 into ArduPilot:master Jul 23, 2024
92 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

6 participants