mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: do not send mode_change event before init complete
This avoids a beep as the flight mode is set during start-up
This commit is contained in:
parent
e68a69e139
commit
79e40b4f6a
@ -30,7 +30,10 @@ static void read_control_switch()
|
||||
if (set_mode(flight_modes[switch_position])) {
|
||||
// play a tone
|
||||
if (control_switch_state.debounced_switch_position != -1) {
|
||||
AP_Notify::events.user_mode_change = 1;
|
||||
// alert user to mode change failure (except if autopilot is just starting up)
|
||||
if (ap.initialised) {
|
||||
AP_Notify::events.user_mode_change = 1;
|
||||
}
|
||||
}
|
||||
|
||||
if(g.ch7_option != AUX_SWITCH_SIMPLE_MODE && g.ch8_option != AUX_SWITCH_SIMPLE_MODE && g.ch7_option != AUX_SWITCH_SUPERSIMPLE_MODE && g.ch8_option != AUX_SWITCH_SUPERSIMPLE_MODE) {
|
||||
|
Loading…
Reference in New Issue
Block a user