diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 532676d346..cbbd21e5a3 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -960,12 +960,13 @@ const AP_Param::Info Copter::var_info[] = { // @User: Standard GSCALAR(throw_motor_start, "THROW_MOT_START", 0), - // @Param: TERRAIN_USE - // @DisplayName: Terrain use control - // @Description: Control how terrain data is used - // @Values: 0:NeverUse, 1:AlwaysUse + // @Param: TERRAIN_FOLLOW + // @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. + // @Values: 0:Do Not Use in RTL and Land 1:Use in RTL and Land // @User: Standard - GSCALAR(terrain_use, "TERRAIN_USE", 0), + GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0), AP_VAREND }; diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 4c772a663f..9364973977 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -179,7 +179,7 @@ public: k_param_disarm_delay, k_param_fs_crash_check, k_param_throw_motor_start, - k_param_terrain_use, // 94 + k_param_terrain_follow, // 94 // 97: RSSI k_param_rssi = 97, @@ -453,7 +453,7 @@ public: AP_Int16 gcs_pid_mask; AP_Int8 throw_motor_start; - AP_Int8 terrain_use; + AP_Int8 terrain_follow; // RC channels RC_Channel rc_1; diff --git a/ArduCopter/terrain.cpp b/ArduCopter/terrain.cpp index 7a042aeeb2..45d91ed90f 100644 --- a/ArduCopter/terrain.cpp +++ b/ArduCopter/terrain.cpp @@ -33,7 +33,7 @@ void Copter::terrain_logging() bool Copter::terrain_use() { #if AP_TERRAIN_AVAILABLE && AC_TERRAIN - return (g.terrain_use > 0); + return (g.terrain_follow > 0); #else return false; #endif