From a1ecd706b7018470caebd19fffdf2988b9cd8e67 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 9 Aug 2021 15:07:32 +0100 Subject: [PATCH] Plane: notify buzzer on every mode change --- ArduPlane/Plane.h | 1 + ArduPlane/RC_Channel.cpp | 9 +-------- ArduPlane/system.cpp | 20 ++++++++++++++++++++ 3 files changed, 22 insertions(+), 8 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index bdbce1192f..a4e19a1230 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1017,6 +1017,7 @@ 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/RC_Channel.cpp b/ArduPlane/RC_Channel.cpp index 17835b05b4..e5e888611d 100644 --- a/ArduPlane/RC_Channel.cpp +++ b/ArduPlane/RC_Channel.cpp @@ -38,14 +38,7 @@ void RC_Channel_Plane::do_aux_function_change_mode(const Mode::Number number, switch(ch_flag) { case AuxSwitchPos::HIGH: { // engage mode (if not possible we remain in current flight mode) - const bool success = plane.set_mode_by_number(number, ModeReason::RC_COMMAND); - if (plane.control_mode != &plane.mode_initializing) { - if (success) { - AP_Notify::events.user_mode_change = 1; - } else { - AP_Notify::events.user_mode_change_failed = 1; - } - } + plane.set_mode_by_number(number, ModeReason::RC_COMMAND); break; } default: diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 753845f4f5..85422ee843 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -202,8 +202,16 @@ 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)) { + AP_Notify::events.user_mode_change = 1; + } return true; } @@ -211,6 +219,10 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) if (&new_mode == &plane.mode_qautotune) { gcs().send_text(MAV_SEVERITY_INFO,"QAUTOTUNE disabled"); set_mode(plane.mode_qhover, ModeReason::UNAVAILABLE); + // make sad noise + if (reason != ModeReason::INITIALISED) { + AP_Notify::events.user_mode_change_failed = 1; + } return false; } #endif @@ -243,6 +255,10 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) // ignore result because if we fail we risk looping at the qautotune check above control_mode->enter(); } + // make sad noise + if (reason != ModeReason::INITIALISED) { + AP_Notify::events.user_mode_change_failed = 1; + } return false; } @@ -262,6 +278,10 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) notify_mode(*control_mode); gcs().send_message(MSG_HEARTBEAT); + // make happy noise + if (reason != ModeReason::INITIALISED) { + AP_Notify::events.user_mode_change = 1; + } return true; }