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:
Randy Mackay 2014-12-15 13:41:43 +09:00
parent e68a69e139
commit 79e40b4f6a
1 changed files with 4 additions and 1 deletions

View File

@ -30,8 +30,11 @@ static void read_control_switch()
if (set_mode(flight_modes[switch_position])) {
// play a tone
if (control_switch_state.debounced_switch_position != -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) {
// set Simple mode using stored paramters from Mission planner