mirror of https://github.com/ArduPilot/ardupilot
Copter: rename TERRAIN_USE to TERRAIN_FOLLOW
This matches plane's parameter name
This commit is contained in:
parent
13c26eab67
commit
74e02d2c82
|
@ -960,12 +960,13 @@ const AP_Param::Info Copter::var_info[] = {
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(throw_motor_start, "THROW_MOT_START", 0),
|
GSCALAR(throw_motor_start, "THROW_MOT_START", 0),
|
||||||
|
|
||||||
// @Param: TERRAIN_USE
|
// @Param: TERRAIN_FOLLOW
|
||||||
// @DisplayName: Terrain use control
|
// @DisplayName: Terrain Following use control
|
||||||
// @Description: Control how terrain data is used
|
// @Description: Control if terrain data is used in RTL and LAND
|
||||||
// @Values: 0:NeverUse, 1:AlwaysUse
|
// @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
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(terrain_use, "TERRAIN_USE", 0),
|
GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0),
|
||||||
|
|
||||||
AP_VAREND
|
AP_VAREND
|
||||||
};
|
};
|
||||||
|
|
|
@ -179,7 +179,7 @@ public:
|
||||||
k_param_disarm_delay,
|
k_param_disarm_delay,
|
||||||
k_param_fs_crash_check,
|
k_param_fs_crash_check,
|
||||||
k_param_throw_motor_start,
|
k_param_throw_motor_start,
|
||||||
k_param_terrain_use, // 94
|
k_param_terrain_follow, // 94
|
||||||
|
|
||||||
// 97: RSSI
|
// 97: RSSI
|
||||||
k_param_rssi = 97,
|
k_param_rssi = 97,
|
||||||
|
@ -453,7 +453,7 @@ public:
|
||||||
AP_Int16 gcs_pid_mask;
|
AP_Int16 gcs_pid_mask;
|
||||||
|
|
||||||
AP_Int8 throw_motor_start;
|
AP_Int8 throw_motor_start;
|
||||||
AP_Int8 terrain_use;
|
AP_Int8 terrain_follow;
|
||||||
|
|
||||||
// RC channels
|
// RC channels
|
||||||
RC_Channel rc_1;
|
RC_Channel rc_1;
|
||||||
|
|
|
@ -33,7 +33,7 @@ void Copter::terrain_logging()
|
||||||
bool Copter::terrain_use()
|
bool Copter::terrain_use()
|
||||||
{
|
{
|
||||||
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
return (g.terrain_use > 0);
|
return (g.terrain_follow > 0);
|
||||||
#else
|
#else
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue