mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_TECS: set FW landing speed if not set
This commit is contained in:
parent
c33ef034b4
commit
5df9b8abf1
@ -116,7 +116,7 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
|
|||||||
|
|
||||||
// @Param: LAND_ARSPD
|
// @Param: LAND_ARSPD
|
||||||
// @DisplayName: Airspeed during landing approach (m/s)
|
// @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
|
// @Range: -1 127
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
Loading…
Reference in New Issue
Block a user