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
Merged
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
8 changes: 8 additions & 0 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -296,6 +296,14 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Standard
ASCALAR(airspeed_max, "AIRSPEED_MAX", AIRSPEED_FBW_MAX),

// @Param: AIRSPEED_STALL
// @DisplayName: Stall airspeed
// @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 stall speed is assumed to be the minimum airspeed speed. Typically set slightly higher then true stall speed. Value is as an indicated (calibrated/apparent) airspeed.
// @Units: m/s
// @Range: 5 75
// @User: Standard
ASCALAR(airspeed_stall, "AIRSPEED_STALL", 0),

// @Param: FBWB_ELEV_REV
// @DisplayName: Fly By Wire elevator reverse
// @Description: Reverse sense of elevator in FBWB and CRUISE modes. When set to 0 up elevator (pulling back on the stick) means to lower altitude. When set to 1, up elevator means to raise altitude.
Expand Down
1 change: 1 addition & 0 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -343,6 +343,7 @@ class Parameters {

k_param_mixing_offset,
k_param_dspoiler_rud_rate,
k_param_airspeed_stall,

k_param_logger = 253, // Logging Group

Expand Down
6 changes: 5 additions & 1 deletion libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -415,7 +415,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(aparm.airspeed_stall)) {
_TASmin = MAX(_TASmin, aparm.airspeed_stall*EAS2TAS*_load_factor);
} else {
_TASmin *= _load_factor;
}
}

if (_TASmax < _TASmin) {
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Vehicle/AP_FixedWing.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ struct AP_FixedWing {
AP_Int16 airspeed_min;
AP_Int16 airspeed_max;
AP_Float airspeed_cruise;
AP_Float airspeed_stall;
AP_Float min_groundspeed;
AP_Int8 crash_detection_enable;
AP_Float roll_limit;
Expand Down
Loading