From 115ed491c0ddc33a81d44bfa0dcea0f2d8739951 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Thu, 15 Mar 2018 13:39:26 +0100 Subject: [PATCH] Copter: Obey RANGEFINDER_ENABLED, AUTOTUNE_ENABLED and AC_TERRAIN build macros --- ArduCopter/Parameters.cpp | 6 ++++++ ArduCopter/Parameters.h | 7 +++++++ ArduCopter/tuning.cpp | 2 ++ 3 files changed, 15 insertions(+) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 9d973195a5..2b8d28a78c 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -169,6 +169,7 @@ const AP_Param::Info Copter::var_info[] = { GSCALAR(rtl_loiter_time, "RTL_LOIT_TIME", RTL_LOITER_TIME), #endif +#if RANGEFINDER_ENABLED == ENABLED // @Param: RNGFND_GAIN // @DisplayName: Rangefinder gain // @Description: Used to adjust the speed with which the target altitude is changed when objects are sensed below the copter @@ -176,6 +177,7 @@ const AP_Param::Info Copter::var_info[] = { // @Increment: 0.01 // @User: Standard GSCALAR(rangefinder_gain, "RNGFND_GAIN", RANGEFINDER_GAIN_DEFAULT), +#endif // @Param: FS_BATT_ENABLE // @DisplayName: Battery Failsafe Enable @@ -777,6 +779,7 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Copter), #endif +#if AUTOTUNE_ENABLED == ENABLED // @Param: AUTOTUNE_AXES // @DisplayName: Autotune axis bitmask // @Description: 1-byte bitmap of axes to autotune @@ -798,6 +801,7 @@ const AP_Param::Info Copter::var_info[] = { // @Range: 0.001 0.006 // @User: Standard GSCALAR(autotune_min_d, "AUTOTUNE_MIN_D", 0.001f), +#endif // @Group: NTF_ // @Path: ../libraries/AP_Notify/AP_Notify.cpp @@ -812,12 +816,14 @@ const AP_Param::Info Copter::var_info[] = { GSCALAR(throw_motor_start, "THROW_MOT_START", 0), #endif +#if AP_TERRAIN_AVAILABLE && AC_TERRAIN // @Param: TERRAIN_FOLLOW // @DisplayName: Terrain Following use control // @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_follow, "TERRAIN_FOLLOW", 0), +#endif // @Group: // @Path: Parameters.cpp diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 8333dc9bcb..51576fe60c 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -390,7 +390,9 @@ public: AP_Int16 rtl_altitude; AP_Int16 rtl_speed_cms; AP_Float rtl_cone_slope; +#if RANGEFINDER_ENABLED == ENABLED AP_Float rangefinder_gain; +#endif AP_Int8 failsafe_battery_enabled; // battery failsafe enabled AP_Float fs_batt_voltage; // battery voltage below which failsafe will be triggered @@ -460,7 +462,10 @@ public: #if MODE_THROW_ENABLED == ENABLED AP_Int8 throw_motor_start; #endif + +#if AP_TERRAIN_AVAILABLE && AC_TERRAIN AP_Int8 terrain_follow; +#endif AP_Int16 rc_speed; // speed of fast RC Channels in Hz @@ -473,9 +478,11 @@ public: AP_Float acro_rp_expo; // Autotune +#if AUTOTUNE_ENABLED == ENABLED AP_Int8 autotune_axis_bitmask; AP_Float autotune_aggressiveness; AP_Float autotune_min_d; +#endif // Note: keep initializers here in the same order as they are declared // above. diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index 30ec7d6de2..9a5a3a95d6 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -140,10 +140,12 @@ void Copter::tuning() { break; #endif +#if RANGEFINDER_ENABLED == ENABLED case TUNING_RANGEFINDER_GAIN: // set rangefinder gain g.rangefinder_gain.set(tuning_value); break; +#endif #if 0 // disabled for now - we need accessor functions