diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 33771a5314..5e3d9b8dee 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -92,7 +92,6 @@ #include // Optical Flow library #include // Filter library #include // APM FIFO Buffer -#include // GPS Lead filter #include // APM relay #include // Photo or video camera #include // Camera/Antenna mount @@ -557,17 +556,12 @@ int32_t roll_axis; int32_t pitch_axis; // Filters -AP_LeadFilter xLeadFilter; // Long GPS lag filter -AP_LeadFilter yLeadFilter; // Lat GPS lag filter #if FRAME_CONFIG == HELI_FRAME LowPassFilterFloat rate_roll_filter; // Rate Roll filter LowPassFilterFloat rate_pitch_filter; // Rate Pitch filter // LowPassFilterFloat rate_yaw_filter; // Rate Yaw filter #endif // HELI_FRAME -// Barometer filter -AverageFilterInt32_Size5 baro_filter; - //////////////////////////////////////////////////////////////////////////////// // Circle Mode / Loiter control //////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 21e0072f2b..385be8ab77 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -28,7 +28,7 @@ static void init_barometer(void) static int32_t read_barometer(void) { barometer.read(); - return baro_filter.apply(barometer.get_altitude() * 100.0f); + return barometer.get_altitude() * 100.0f; } // return sonar altitude in centimeters