Skip to content

Commit

Permalink
AP_TECS: Add a seperate stall speed parameter used for minimum speed …
Browse files Browse the repository at this point in the history
…scaling

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.
  • Loading branch information
WickedShell committed Jul 3, 2024
1 parent 38ca478 commit dec5c40
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 1 deletion.
15 changes: 14 additions & 1 deletion libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -283,6 +283,15 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
// @User: Advanced
AP_GROUPINFO("HDEM_TCONST", 33, AP_TECS, _hgt_dem_tconst, 3.0f),

// @Param: STALL_SPEED
// @DisplayName: Stall speed used for scaling minimum speed
// @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 speed is scaled from the minimum speed. Typically set slightly higher then true stall speed.
// @Range: 5.0 75.0
// @Units: m/s
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("STALL_SPEED", 34, AP_TECS, _stall_speed, 0),

AP_GROUPEND
};

Expand Down Expand Up @@ -415,7 +424,11 @@ 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;
if (is_positive(_stall_speed)) {
_TASmin = MAX(_TASmin, _stall_speed*EAS2TAS*_load_factor);
} else {
_TASmin *= _load_factor;
}
}

if (_TASmax < _TASmin) {
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_TECS/AP_TECS.h
Original file line number Diff line number Diff line change
Expand Up @@ -196,6 +196,7 @@ class AP_TECS {
AP_Int32 _options;
AP_Float _flare_holdoff_hgt;
AP_Float _hgt_dem_tconst;
AP_Float _stall_speed;

enum {
OPTION_GLIDER_ONLY=(1<<0),
Expand Down

0 comments on commit dec5c40

Please sign in to comment.