mirror of https://github.com/ArduPilot/ardupilot
Copter: fix TERRAIN_FOLLOW parameter description
Thanks OXINARF
This commit is contained in:
parent
3d31c3b936
commit
a6b6fb2473
|
@ -962,7 +962,6 @@ const AP_Param::Info Copter::var_info[] = {
|
||||||
|
|
||||||
// @Param: TERRAIN_FOLLOW
|
// @Param: TERRAIN_FOLLOW
|
||||||
// @DisplayName: Terrain Following use control
|
// @DisplayName: Terrain Following use control
|
||||||
// @Description: Control if terrain data is used in RTL and LAND
|
|
||||||
// @Description: This enables terrain following for RTL and LAND flight modes. To use this option TERRAIN_ENABLE must be 1 and the GCS must support sending terrain data to the aircraft. In RTL the RTL_ALT will be considered a height above the terrain. In LAND mode the vehicle will slow to LAND_SPEED 10m above terrain (instead of 10m above home). This parameter does not affect AUTO and Guided which use a per-command flag to determine if the height is above-home, absolute or above-terrain.
|
// @Description: This enables terrain following for RTL and LAND flight modes. To use this option TERRAIN_ENABLE must be 1 and the GCS must support sending terrain data to the aircraft. In RTL the RTL_ALT will be considered a height above the terrain. In LAND mode the vehicle will slow to LAND_SPEED 10m above terrain (instead of 10m above home). This parameter does not affect AUTO and Guided which use a per-command flag to determine if the height is above-home, absolute or above-terrain.
|
||||||
// @Values: 0:Do Not Use in RTL and Land 1:Use in RTL and Land
|
// @Values: 0:Do Not Use in RTL and Land 1:Use in RTL and Land
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
|
Loading…
Reference in New Issue