mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AC fix some Parameter units
This commit is contained in:
parent
0996782582
commit
4be10b4418
@ -30,8 +30,8 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Param: ALT_HOLD_RTL
|
// @Param: ALT_HOLD_RTL
|
||||||
// @DisplayName: RTL Altitude
|
// @DisplayName: RTL Altitude
|
||||||
// @Description: This is the altitude the model will move to before Returning to Launch. Set to zero to return at current altitude.
|
// @Description: This is the altitude the model will move to before Returning to Launch. Set to zero to return at current altitude.
|
||||||
// @Units: Meters
|
// @Units: centimeters
|
||||||
// @Range: 0 400
|
// @Range: 0 4000
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(RTL_altitude, "ALT_HOLD_RTL", RTL_HOLD_ALT),
|
GSCALAR(RTL_altitude, "ALT_HOLD_RTL", RTL_HOLD_ALT),
|
||||||
@ -92,9 +92,9 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Param: APPROACH_ALT
|
// @Param: APPROACH_ALT
|
||||||
// @DisplayName: RTL Approach Altitude
|
// @DisplayName: RTL Approach Altitude
|
||||||
// @Description: This is the altitude the vehicle will move to as the final stage of Returning to Launch. Set to zero to land.
|
// @Description: This is the altitude the vehicle will move to as the final stage of Returning to Launch. Set to zero to land.
|
||||||
// @Units: Meters
|
// @Units: centimeters
|
||||||
// @Range: 1 10
|
// @Range: 1 1000
|
||||||
// @Increment: .1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(rtl_approach_alt, "APPROACH_ALT", RTL_APPROACH_ALT),
|
GSCALAR(rtl_approach_alt, "APPROACH_ALT", RTL_APPROACH_ALT),
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user