From 2f7df9ef4ca6c8907debb2059e31ecc098899b31 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 10 May 2022 17:53:32 +1000 Subject: [PATCH] Blimp: run prearm checks on all vehicles @1Hz, displaying @0.0333Hz --- Blimp/AP_Arming.cpp | 16 ---------------- Blimp/AP_Arming.h | 2 -- Blimp/Blimp.cpp | 2 -- Blimp/config.h | 4 ---- 4 files changed, 24 deletions(-) diff --git a/Blimp/AP_Arming.cpp b/Blimp/AP_Arming.cpp index e02d1f4fe5..17b12078a3 100644 --- a/Blimp/AP_Arming.cpp +++ b/Blimp/AP_Arming.cpp @@ -1,21 +1,5 @@ #include "Blimp.h" - -// performs pre-arm checks. expects to be called at 1hz. -void AP_Arming_Blimp::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 (pre_arm_display_counter >= PREARM_DISPLAY_PERIOD) { - display_fail = true; - pre_arm_display_counter = 0; - } - - pre_arm_checks(display_fail); -} - bool AP_Arming_Blimp::pre_arm_checks(bool display_failure) { const bool passed = run_pre_arm_checks(display_failure); diff --git a/Blimp/AP_Arming.h b/Blimp/AP_Arming.h index 8955e09362..b092fa9ee4 100644 --- a/Blimp/AP_Arming.h +++ b/Blimp/AP_Arming.h @@ -19,8 +19,6 @@ public: AP_Arming_Blimp(const AP_Arming_Blimp &other) = delete; AP_Arming_Blimp &operator=(const AP_Arming_Blimp&) = 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/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index 7d902acc12..62f61f1fa9 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -204,8 +204,6 @@ void Blimp::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/Blimp/config.h b/Blimp/config.h index fd386ad5f4..776dcb4f8c 100644 --- a/Blimp/config.h +++ b/Blimp/config.h @@ -132,10 +132,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