Sub: remove unused TERRAIN_FOLLOW parameter

This commit is contained in:
Randy Mackay 2019-12-12 14:49:34 +09:00
parent 21ea7902cf
commit b1ccf5b9d5
4 changed files with 1 additions and 24 deletions

View File

@ -586,15 +586,6 @@ const AP_Param::Info Sub::var_info[] = {
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
GOBJECT(notify, "NTF_", AP_Notify),
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
// @Param: TERRAIN_FOLLOW
// @DisplayName: Terrain Following use control
// @Description: This enables terrain following for RTL and SURFACE 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 SURFACE,1:Use in RTL and SURFACE
// @User: Standard
GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0),
#endif
// @Group:
// @Path: Parameters.cpp
GOBJECT(g2, "", ParametersG2),

View File

@ -186,7 +186,7 @@ public:
k_param_gcs_pid_mask = 178,
k_param_throttle_filt,
k_param_throttle_deadzone, // Used in auto-throttle modes
k_param_terrain_follow = 182,
k_param_terrain_follow = 182, // deprecated
k_param_rc_feel_rp,
k_param_throttle_gain,
k_param_cam_tilt_center, // deprecated
@ -259,10 +259,6 @@ public:
AP_Float fs_ekf_thresh;
AP_Int16 gcs_pid_mask;
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
AP_Int8 terrain_follow;
#endif
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
AP_Float gain_default;

View File

@ -572,7 +572,6 @@ private:
#endif
void terrain_update();
void terrain_logging();
bool terrain_use();
void init_ardupilot();
void startup_INS_ground();
bool position_ok();

View File

@ -27,12 +27,3 @@ void Sub::terrain_logging()
#endif
}
// should we use terrain data for things including the home altitude
bool Sub::terrain_use()
{
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
return (g.terrain_follow > 0);
#else
return false;
#endif
}