diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 3b311bf037..6839e2390e 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -4,22 +4,6 @@ #include #endif -// performs pre-arm checks. expects to be called at 1hz. -void AP_Arming_Copter::update(void) -{ - // perform pre-arm checks & display failures every 30 seconds - static uint8_t pre_arm_display_counter = PREARM_DISPLAY_PERIOD/2; - pre_arm_display_counter++; - bool display_fail = false; - if ((_arming_options & uint32_t(AP_Arming::ArmingOptions::DISABLE_PREARM_DISPLAY)) == 0 && - pre_arm_display_counter >= PREARM_DISPLAY_PERIOD) { - display_fail = true; - pre_arm_display_counter = 0; - } - - pre_arm_checks(display_fail); -} - bool AP_Arming_Copter::pre_arm_checks(bool display_failure) { const bool passed = run_pre_arm_checks(display_failure); diff --git a/ArduCopter/AP_Arming.h b/ArduCopter/AP_Arming.h index ae705b70e4..e1a32ed20a 100644 --- a/ArduCopter/AP_Arming.h +++ b/ArduCopter/AP_Arming.h @@ -19,8 +19,6 @@ public: AP_Arming_Copter(const AP_Arming_Copter &other) = delete; AP_Arming_Copter &operator=(const AP_Arming_Copter&) = delete; - void update(void); - bool rc_calibration_checks(bool display_failure) override; bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override; diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index bec597a2f8..656fea9d30 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -581,8 +581,6 @@ void Copter::one_hz_loop() Log_Write_Data(LogDataID::AP_STATE, ap.value); } - arming.update(); - if (!motors->armed()) { // make it possible to change ahrs orientation at runtime during initial config ahrs.update_orientation(); diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 9a971cc66d..dee8e31770 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -145,10 +145,6 @@ #define FS_TERRAIN_TIMEOUT_MS 5000 // 5 seconds of missing terrain data will trigger failsafe (RTL) #endif -#ifndef PREARM_DISPLAY_PERIOD -# define PREARM_DISPLAY_PERIOD 30 -#endif - // pre-arm baro vs inertial nav max alt disparity #ifndef PREARM_MAX_ALT_DISPARITY_CM # define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters