From 5df9b8abf164cebbd1cb370ebba34ae5f9881cec Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 25 Jun 2023 14:35:45 -0500 Subject: [PATCH] AP_TECS: set FW landing speed if not set --- libraries/AP_TECS/AP_TECS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 1f6d2a4ee1..c87bd020b0 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -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 not used during landing. + // @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. // @Range: -1 127 // @Increment: 1 // @User: Standard