From 90f2bf3ba2cd64b33d26450991a165e4de398fd9 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Jul 2022 22:51:21 +0100 Subject: [PATCH] Plane: remove duplicate last mode reason --- ArduPlane/Plane.h | 1 - ArduPlane/events.cpp | 6 +++--- ArduPlane/system.cpp | 5 +---- 3 files changed, 4 insertions(+), 8 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 097255a8d0..398cdb93a8 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1057,7 +1057,6 @@ private: bool set_mode(Mode& new_mode, const ModeReason reason); bool set_mode(const uint8_t mode, const ModeReason reason) override; bool set_mode_by_number(const Mode::Number new_mode_number, const ModeReason reason); - ModeReason _last_reason; void check_long_failsafe(); void check_short_failsafe(); void startup_INS_ground(void); diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 0a4500d64d..519464b443 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -200,11 +200,11 @@ void Plane::failsafe_short_off_event(ModeReason reason) // We're back in radio contact gcs().send_text(MAV_SEVERITY_WARNING, "Short Failsafe Cleared"); failsafe.state = FAILSAFE_NONE; - //restore entry mode if desired but check that our current mode is still due to failsafe - if ( _last_reason == ModeReason::RADIO_FAILSAFE) { + // restore entry mode if desired but check that our current mode is still due to failsafe + if (control_mode_reason == ModeReason::RADIO_FAILSAFE) { set_mode_by_number(failsafe.saved_mode_number, ModeReason::RADIO_FAILSAFE_RECOVERY); gcs().send_text(MAV_SEVERITY_INFO,"Flight mode %s restored",control_mode->name()); - } + } } void Plane::failsafe_long_off_event(ModeReason reason) diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 5ae059fa8f..9551f70680 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -204,14 +204,11 @@ void Plane::startup_ground(void) bool Plane::set_mode(Mode &new_mode, const ModeReason reason) { - // update last reason - const ModeReason last_reason = _last_reason; - _last_reason = reason; if (control_mode == &new_mode) { // don't switch modes if we are already in the correct mode. // only make happy noise if using a difent method to switch, this stops beeping for repeated change mode requests from GCS - if ((reason != last_reason) && (reason != ModeReason::INITIALISED)) { + if ((reason != control_mode_reason) && (reason != ModeReason::INITIALISED)) { AP_Notify::events.user_mode_change = 1; } return true;