From 6881f42cbac78d72cbf5bd36b3efe8bf6fc59f2b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 25 Jul 2024 15:05:02 +1000 Subject: [PATCH] Copter: add a Mode method to disable crash check prevents looking for specific modes in the crash checker --- ArduCopter/crash_check.cpp | 4 ++-- ArduCopter/mode.h | 3 +++ 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 0a377419af..7bb3da1bb5 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -42,7 +42,7 @@ void Copter::crash_check() } // return immediately if we are not in an angle stabilize flight mode or we are flipping - if (flightmode->mode_number() == Mode::Number::ACRO || flightmode->mode_number() == Mode::Number::FLIP) { + if (flightmode->disable_crash_check()) { crash_counter = 0; return; } @@ -273,7 +273,7 @@ void Copter::parachute_check() } // return immediately if we are not in an angle stabilize flight mode or we are flipping - if (flightmode->mode_number() == Mode::Number::ACRO || flightmode->mode_number() == Mode::Number::FLIP) { + if (flightmode->disable_crash_check()) { control_loss_count = 0; return; } diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 25b1b07027..68bf46adc8 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -128,6 +128,7 @@ public: virtual bool allows_save_trim() const { return false; } virtual bool allows_autotune() const { return false; } virtual bool allows_flip() const { return false; } + virtual bool disable_crash_check() const { return false; } #if FRAME_CONFIG == HELI_FRAME virtual bool allows_inverted() const { return false; }; @@ -420,6 +421,7 @@ public: void air_mode_aux_changed(); bool allows_save_trim() const override { return true; } bool allows_flip() const override { return true; } + bool disable_crash_check() const override { return true; } protected: @@ -911,6 +913,7 @@ public: bool has_manual_throttle() const override { return false; } bool allows_arming(AP_Arming::Method method) const override { return false; }; bool is_autopilot() const override { return false; } + bool disable_crash_check() const override { return true; } protected: