diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 6408a4db84..094f5dbfe9 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -108,7 +108,6 @@ #include // ArduPilot Mega Analog to Digital Converter Library #include #include -#include // Baro glitch protection library #include // ArduPilot Mega Magnetometer Library #include // ArduPilot Mega Vector/Matrix math Library #include // Curve used to linearlise throttle pwm to thrust @@ -265,8 +264,6 @@ static AP_Int8 *flight_modes = &g.flight_mode1; static AP_Baro barometer; -static Baro_Glitch baro_glitch(barometer); - #if CONFIG_COMPASS == HAL_COMPASS_PX4 static AP_Compass_PX4 compass; #elif CONFIG_COMPASS == HAL_COMPASS_VRBRAIN @@ -606,9 +603,9 @@ static float G_Dt = 0.02; // Inertial Navigation //////////////////////////////////////////////////////////////////////////////// #if AP_AHRS_NAVEKF_AVAILABLE -static AP_InertialNav_NavEKF inertial_nav(ahrs, barometer, gps_glitch, baro_glitch); +static AP_InertialNav_NavEKF inertial_nav(ahrs, barometer, gps_glitch); #else -static AP_InertialNav inertial_nav(ahrs, barometer, gps_glitch, baro_glitch); +static AP_InertialNav inertial_nav(ahrs, barometer, gps_glitch); #endif //////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index b10365e888..bfa681ea4c 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -136,7 +136,7 @@ public: k_param_altitude_limit, // deprecated - remove k_param_fence, k_param_gps_glitch, - k_param_baro_glitch, // 71 + k_param_baro_glitch, // 71 - deprecated // // 75: Singlecopter, CoaxCopter diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde index 3417c16758..f94ab492cc 100644 --- a/ArduCopter/Parameters.pde +++ b/ArduCopter/Parameters.pde @@ -907,10 +907,6 @@ const AP_Param::Info var_info[] PROGMEM = { // @Path: ../libraries/AP_GPS/AP_GPS_Glitch.cpp GOBJECT(gps_glitch, "GPSGLITCH_", GPS_Glitch), - // @Group: BAROGLTCH_ - // @Path: ../libraries/AP_Baro/AP_Baro_Glitch.cpp - GOBJECT(baro_glitch, "BAROGLTCH_", Baro_Glitch), - #if FRAME_CONFIG == HELI_FRAME // @Group: H_ // @Path: ../libraries/AP_Motors/AP_MotorsHeli.cpp diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 13d77af0da..ad7489b06a 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -8,8 +8,6 @@ static void init_barometer(bool full_calibration) }else{ barometer.update_calibration(); } - // reset glitch protection to use new baro alt - baro_glitch.reset(); gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete")); } @@ -22,18 +20,6 @@ static void read_barometer(void) } baro_alt = barometer.get_altitude() * 100.0f; baro_climbrate = barometer.get_climb_rate() * 100.0f; - - // run glitch protection and update AP_Notify if home has been initialised - baro_glitch.check_alt(); - bool report_baro_glitch = (baro_glitch.glitching() && !ap.usb_connected && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); - if (AP_Notify::flags.baro_glitching != report_baro_glitch) { - if (baro_glitch.glitching()) { - Log_Write_Error(ERROR_SUBSYSTEM_BARO, ERROR_CODE_BARO_GLITCH); - } else { - Log_Write_Error(ERROR_SUBSYSTEM_BARO, ERROR_CODE_ERROR_RESOLVED); - } - AP_Notify::flags.baro_glitching = report_baro_glitch; - } } #if CONFIG_SONAR == ENABLED