From 90220e83ac6e44127bba22dd7f3fc421ae9f1416 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 17 Nov 2022 09:07:59 +0900 Subject: [PATCH] Copter: remove unused definitions --- ArduCopter/config.h | 21 --------------------- 1 file changed, 21 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 0c9b5628a4..b1e96c2c37 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -84,10 +84,6 @@ # define RANGEFINDER_FILT_DEFAULT 0.5f // filter for rangefinder distance #endif -#ifndef SURFACE_TRACKING_VELZ_MAX - # define SURFACE_TRACKING_VELZ_MAX 150 // max vertical speed change while surface tracking with rangefinder -#endif - #ifndef SURFACE_TRACKING_TIMEOUT_MS # define SURFACE_TRACKING_TIMEOUT_MS 1000 // surface tracking target alt will reset to current rangefinder alt after this many milliseconds without a good rangefinder alt #endif @@ -108,28 +104,11 @@ # define MAV_SYSTEM_ID 1 #endif - -////////////////////////////////////////////////////////////////////////////// -// Battery monitoring -// -#ifndef BOARD_VOLTAGE_MIN - # define BOARD_VOLTAGE_MIN 4.3f // min board voltage in volts for pre-arm checks -#endif - -#ifndef BOARD_VOLTAGE_MAX - # define BOARD_VOLTAGE_MAX 5.8f // max board voltage in volts for pre-arm checks -#endif - // prearm GPS hdop check #ifndef GPS_HDOP_GOOD_DEFAULT # define GPS_HDOP_GOOD_DEFAULT 140 // minimum hdop that represents a good position. used during pre-arm checks if fence is enabled #endif -// GCS failsafe -#ifndef FS_GCS - # define FS_GCS DISABLED -#endif - // missing terrain data failsafe #ifndef FS_TERRAIN_TIMEOUT_MS #define FS_TERRAIN_TIMEOUT_MS 5000 // 5 seconds of missing terrain data will trigger failsafe (RTL)