Plane: notify buzzer on every mode change

This commit is contained in:
Iampete1 2021-08-09 15:07:32 +01:00 committed by Andrew Tridgell
parent 2a2cde68ef
commit a1ecd706b7
3 changed files with 22 additions and 8 deletions

View File

@ -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);

View File

@ -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:

View File

@ -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;
}