mirror of https://github.com/ArduPilot/ardupilot
Copter: change RTL_ALT_MIN from 200cm to 30cm
This commit is contained in:
parent
9a092e4e3a
commit
251db3f414
|
@ -102,7 +102,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @DisplayName: RTL Altitude
|
||||
// @Description: The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude.
|
||||
// @Units: cm
|
||||
// @Range: 200 300000
|
||||
// @Range: 30 300000
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(rtl_altitude, "RTL_ALT", RTL_ALT),
|
||||
|
|
|
@ -434,7 +434,7 @@
|
|||
#endif
|
||||
|
||||
#ifndef RTL_ALT_MIN
|
||||
# define RTL_ALT_MIN 200 // min height above ground for RTL (i.e 2m)
|
||||
# define RTL_ALT_MIN 30 // min height above ground for RTL (i.e 30cm)
|
||||
#endif
|
||||
|
||||
#ifndef RTL_CLIMB_MIN_DEFAULT
|
||||
|
|
Loading…
Reference in New Issue