ArduPlane: convert ARSPD_FBW_MIN/MAX to AIRSPEED_MIN and AIRSPEED_MAX

This commit is contained in:
Andrew Tridgell 2024-01-18 16:37:41 +11:00
parent a87dea0139
commit 912e2f224b
4 changed files with 20 additions and 20 deletions

View File

@ -92,7 +92,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
}
if (plane.aparm.airspeed_min < MIN_AIRSPEED_MIN) {
check_failed(display_failure, "ARSPD_FBW_MIN too low (%i < %i)", plane.aparm.airspeed_min.get(), MIN_AIRSPEED_MIN);
check_failed(display_failure, "AIRSPEED_MIN too low (%i < %i)", plane.aparm.airspeed_min.get(), MIN_AIRSPEED_MIN);
ret = false;
}

View File

@ -267,28 +267,35 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: STALL_PREVENTION
// @DisplayName: Enable stall prevention
// @Description: Enables roll limits at low airspeed in roll limiting flight modes. Roll limits based on aerodynamic load factor in turns and scale on ARSPD_FBW_MIN that must be set correctly. Without airspeed sensor, uses synthetic airspeed from wind speed estimate that may both be inaccurate.
// @Description: Enables roll limits at low airspeed in roll limiting flight modes. Roll limits based on aerodynamic load factor in turns and scale on AIRSPEED_MIN that must be set correctly. Without airspeed sensor, uses synthetic airspeed from wind speed estimate that may both be inaccurate.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
ASCALAR(stall_prevention, "STALL_PREVENTION", 1),
// @Param: ARSPD_FBW_MIN
// @Param: AIRSPEED_CRUISE
// @DisplayName: Target cruise airspeed
// @Description: Target cruise airspeed in m/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
// @Units: m/s
// @User: Standard
ASCALAR(airspeed_cruise, "AIRSPEED_CRUISE", AIRSPEED_CRUISE),
// @Param: AIRSPEED_MIN
// @DisplayName: Minimum Airspeed
// @Description: Minimum airspeed demanded in automatic throttle modes. Should be set to 20% higher than level flight stall speed.
// @Units: m/s
// @Range: 5 100
// @Increment: 1
// @User: Standard
ASCALAR(airspeed_min, "ARSPD_FBW_MIN", AIRSPEED_FBW_MIN),
ASCALAR(airspeed_min, "AIRSPEED_MIN", AIRSPEED_FBW_MIN),
// @Param: ARSPD_FBW_MAX
// @Param: AIRSPEED_MAX
// @DisplayName: Maximum Airspeed
// @Description: Maximum airspeed demanded in automatic throttle modes. Should be set slightly less than level flight speed at THR_MAX and also at least 50% above ARSPD_FBW_MIN to allow for accurate TECS altitude control.
// @Description: Maximum airspeed demanded in automatic throttle modes. Should be set slightly less than level flight speed at THR_MAX and also at least 50% above AIRSPEED_MIN to allow for accurate TECS altitude control.
// @Units: m/s
// @Range: 5 100
// @Increment: 1
// @User: Standard
ASCALAR(airspeed_max, "ARSPD_FBW_MAX", AIRSPEED_FBW_MAX),
ASCALAR(airspeed_max, "AIRSPEED_MAX", AIRSPEED_FBW_MAX),
// @Param: FBWB_ELEV_REV
// @DisplayName: Fly By Wire elevator reverse
@ -410,7 +417,7 @@ const AP_Param::Info Plane::var_info[] = {
// @Param: THROTTLE_NUDGE
// @DisplayName: Throttle nudge enable
// @Description: When enabled, this uses the throttle input in auto-throttle modes to 'nudge' the throttle or airspeed to higher or lower values. When you have an airspeed sensor the nudge affects the target airspeed, so that throttle inputs above 50% will increase the target airspeed from AIRSPEED_CRUISE up to a maximum of ARSPD_FBW_MAX. When no airspeed sensor is enabled the throttle nudge will push up the target throttle for throttle inputs above 50%.
// @Description: When enabled, this uses the throttle input in auto-throttle modes to 'nudge' the throttle or airspeed to higher or lower values. When you have an airspeed sensor the nudge affects the target airspeed, so that throttle inputs above 50% will increase the target airspeed from AIRSPEED_CRUISE up to a maximum of AIRSPEED_MAX. When no airspeed sensor is enabled the throttle nudge will push up the target throttle for throttle inputs above 50%.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
GSCALAR(throttle_nudge, "THROTTLE_NUDGE", 1),
@ -621,13 +628,6 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
// @Param: AIRSPEED_CRUISE
// @DisplayName: Target cruise airspeed
// @Description: Target cruise airspeed in m/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.
// @Units: m/s
// @User: Standard
ASCALAR(airspeed_cruise, "AIRSPEED_CRUISE", AIRSPEED_CRUISE),
// @Param: SCALING_SPEED
// @DisplayName: speed used for speed scaling calculations
// @Description: Airspeed in m/s to use when calculating surface speed scaling. Note that changing this value will affect all PID values

View File

@ -4553,10 +4553,10 @@ enabled.
When in stabilised manual throttle modes this option has the effect of
limiting how much bank angle you can demand when close to the
configured minimum airspeed (from ARSPD_FBW_MIN). That means when in
FBWA mode if you try to turn hard while close to ARSPD_FBW_MIN it will
configured minimum airspeed (from AIRSPEED_MIN). That means when in
FBWA mode if you try to turn hard while close to AIRSPEED_MIN it will
limit the bank angle to an amount that will keep the speed above
ARSPD_FBW_MIN times the aerodynamic load factor. It will always allow
AIRSPEED_MIN times the aerodynamic load factor. It will always allow
you at bank at least 25 degrees however, to ensure you keep some
maneuverability if the airspeed estimate is incorrect.
@ -4569,7 +4569,7 @@ handle the demanded turn. After the turn is complete the minimum
airspeed will drop back to the normal level.
This change won't completely eliminate stalls of course, but it should
make them less likely if you properly configure ARSPD_FBW_MIN for your
make them less likely if you properly configure AIRSPEED_MIN for your
aircraft.
PX4IO based RC override code

View File

@ -4655,7 +4655,7 @@ bool QuadPlane::landing_with_fixed_wing_spiral_approach(void) const
setup scaling of roll and pitch angle P gains to match fixed wing gains
we setup the angle P gain to match fixed wing at high speed (above
ARSPD_FBW_MIN) where fixed wing surfaces are presumed to
AIRSPEED_MIN) where fixed wing surfaces are presumed to
dominate. At lower speeds we use the multicopter angle P gains.
*/
void QuadPlane::setup_rp_fw_angle_gains(void)