Copter: notify buzzer on every flight mode change
This commit is contained in:
parent
ca35d01baa
commit
9f5591be02
@ -804,6 +804,7 @@ private:
|
||||
// mode.cpp
|
||||
bool set_mode(Mode::Number mode, ModeReason reason);
|
||||
bool set_mode(const uint8_t new_mode, const ModeReason reason) override;
|
||||
ModeReason _last_reason;
|
||||
// called when an attempt to change into a mode is unsuccessful:
|
||||
void mode_change_failed(const Mode *mode, const char *reason);
|
||||
uint8_t get_mode() const override { return (uint8_t)flightmode->mode_number(); }
|
||||
|
@ -22,19 +22,9 @@ void RC_Channel_Copter::mode_switch_changed(modeswitch_pos_t new_pos)
|
||||
}
|
||||
|
||||
if (!copter.set_mode((Mode::Number)copter.flight_modes[new_pos].get(), ModeReason::RC_COMMAND)) {
|
||||
// alert user to mode change failure
|
||||
if (copter.ap.initialised) {
|
||||
AP_Notify::events.user_mode_change_failed = 1;
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
// play a tone
|
||||
// alert user to mode change (except if autopilot is just starting up)
|
||||
if (copter.ap.initialised) {
|
||||
AP_Notify::events.user_mode_change = 1;
|
||||
}
|
||||
|
||||
if (!rc().find_channel_for_option(AUX_FUNC::SIMPLE_MODE) &&
|
||||
!rc().find_channel_for_option(AUX_FUNC::SUPERSIMPLE_MODE)) {
|
||||
// if none of the Aux Switches are set to Simple or Super Simple Mode then
|
||||
@ -131,14 +121,7 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
|
||||
switch(ch_flag) {
|
||||
case AuxSwitchPos::HIGH: {
|
||||
// engage mode (if not possible we remain in current flight mode)
|
||||
const bool success = copter.set_mode(mode, ModeReason::RC_COMMAND);
|
||||
if (copter.ap.initialised) {
|
||||
if (success) {
|
||||
AP_Notify::events.user_mode_change = 1;
|
||||
} else {
|
||||
AP_Notify::events.user_mode_change_failed = 1;
|
||||
}
|
||||
}
|
||||
copter.set_mode(mode, ModeReason::RC_COMMAND);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
|
@ -182,6 +182,10 @@ void Copter::mode_change_failed(const Mode *mode, const char *reason)
|
||||
{
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to %s failed: %s", mode->name(), reason);
|
||||
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode->mode_number()));
|
||||
// make sad noise
|
||||
if (copter.ap.initialised) {
|
||||
AP_Notify::events.user_mode_change_failed = 1;
|
||||
}
|
||||
}
|
||||
|
||||
// set_mode - change flight mode and perform any necessary initialisation
|
||||
@ -190,10 +194,17 @@ void Copter::mode_change_failed(const Mode *mode, const char *reason)
|
||||
// ACRO, STABILIZE, ALTHOLD, LAND, DRIFT and SPORT can always be set successfully but the return state of other flight modes should be checked and the caller should deal with failures appropriately
|
||||
bool Copter::set_mode(Mode::Number mode, ModeReason reason)
|
||||
{
|
||||
// update last reason
|
||||
const ModeReason last_reason = _last_reason;
|
||||
_last_reason = reason;
|
||||
|
||||
// return immediately if we are already in the desired mode
|
||||
if (mode == flightmode->mode_number()) {
|
||||
control_mode_reason = reason;
|
||||
// make happy noise
|
||||
if (copter.ap.initialised && (reason != last_reason)) {
|
||||
AP_Notify::events.user_mode_change = 1;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -306,6 +317,11 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
|
||||
// update notify object
|
||||
notify_flight_mode();
|
||||
|
||||
// make happy noise
|
||||
if (copter.ap.initialised) {
|
||||
AP_Notify::events.user_mode_change = 1;
|
||||
}
|
||||
|
||||
// return success
|
||||
return true;
|
||||
}
|
||||
|
@ -199,7 +199,6 @@ void Copter::init_ardupilot()
|
||||
if (!set_mode((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED)) {
|
||||
// set mode to STABILIZE will trigger mode change notification to pilot
|
||||
set_mode(Mode::Number::STABILIZE, ModeReason::UNAVAILABLE);
|
||||
AP_Notify::events.user_mode_change_failed = 1;
|
||||
}
|
||||
|
||||
// flag that initialisation has completed
|
||||
|
Loading…
Reference in New Issue
Block a user