AP_TECS: 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 8fd0bc6f6a
commit d65809ffc1
1 changed files with 2 additions and 2 deletions

View File

@ -108,7 +108,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
// @Param: SINK_MAX
// @DisplayName: Maximum Descent Rate (metres/sec)
// @Description: Maximum demanded descent rate. Do not set higher than the vertical speed the aircraft can maintain at THR_MIN, TECS_PITCH_MIN, and ARSPD_FBW_MAX.
// @Description: Maximum demanded descent rate. Do not set higher than the vertical speed the aircraft can maintain at THR_MIN, TECS_PITCH_MIN, and AIRSPEED_MAX.
// @Increment: 0.1
// @Range: 0.0 20.0
// @User: Standard
@ -116,7 +116,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
// @Param: LAND_ARSPD
// @DisplayName: Airspeed during landing approach (m/s)
// @Description: When performing an autonomus landing, this value is used as the goal airspeed during approach. Max airspeed allowed is Trim Airspeed or ARSPD_FBW_MAX as defined by LAND_OPTIONS bitmask. Note that this parameter is not useful if your platform does not have an airspeed sensor (use TECS_LAND_THR instead). If negative then this value is halfway between ARSPD_FBW_MIN and TRIM_CRUISE_CM speed for fixed wing autolandings.
// @Description: When performing an autonomus landing, this value is used as the goal airspeed during approach. Max airspeed allowed is Trim Airspeed or AIRSPEED_MAX as defined by LAND_OPTIONS bitmask. Note that this parameter is not useful if your platform does not have an airspeed sensor (use TECS_LAND_THR instead). If negative then this value is halfway between AIRSPEED_MIN and TRIM_CRUISE_CM speed for fixed wing autolandings.
// @Range: -1 127
// @Increment: 1
// @User: Standard