ToneAlarm_PX4: remove user_mode_init flag
Replaced by an initialised check in the main ArduCopter flight code
This commit is contained in:
parent
562f3e7382
commit
e68a69e139
@ -79,7 +79,6 @@ bool ToneAlarm_PX4::init()
|
|||||||
flags.armed = AP_Notify::flags.armed;
|
flags.armed = AP_Notify::flags.armed;
|
||||||
flags.failsafe_battery = AP_Notify::flags.failsafe_battery;
|
flags.failsafe_battery = AP_Notify::flags.failsafe_battery;
|
||||||
flags.pre_arm_check = 1;
|
flags.pre_arm_check = 1;
|
||||||
flags.user_mode_initialized = 0;
|
|
||||||
_cont_tone_playing = -1;
|
_cont_tone_playing = -1;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -149,7 +148,7 @@ void ToneAlarm_PX4::update()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// notify the user when their mode change was successful
|
// notify the user when their mode change was successful
|
||||||
if (AP_Notify::events.user_mode_change && flags.user_mode_initialized) {
|
if (AP_Notify::events.user_mode_change) {
|
||||||
if (AP_Notify::flags.armed) {
|
if (AP_Notify::flags.armed) {
|
||||||
play_tone(AP_NOTIFY_PX4_TONE_LOUD_NEU_FEEDBACK);
|
play_tone(AP_NOTIFY_PX4_TONE_LOUD_NEU_FEEDBACK);
|
||||||
} else {
|
} else {
|
||||||
@ -158,7 +157,7 @@ void ToneAlarm_PX4::update()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// notify the user when their mode change failed
|
// notify the user when their mode change failed
|
||||||
if (AP_Notify::events.user_mode_change_failed && flags.user_mode_initialized) {
|
if (AP_Notify::events.user_mode_change_failed) {
|
||||||
if (AP_Notify::flags.armed) {
|
if (AP_Notify::flags.armed) {
|
||||||
play_tone(AP_NOTIFY_PX4_TONE_LOUD_NEG_FEEDBACK);
|
play_tone(AP_NOTIFY_PX4_TONE_LOUD_NEG_FEEDBACK);
|
||||||
} else {
|
} else {
|
||||||
@ -166,11 +165,6 @@ void ToneAlarm_PX4::update()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//set user_mode_initialized
|
|
||||||
if (AP_Notify::events.user_mode_change || AP_Notify::events.user_mode_change_failed) {
|
|
||||||
flags.user_mode_initialized = 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
// failsafe initiated mode change
|
// failsafe initiated mode change
|
||||||
if(AP_Notify::events.failsafe_mode_change) {
|
if(AP_Notify::events.failsafe_mode_change) {
|
||||||
play_tone(AP_NOTIFY_PX4_TONE_LOUD_ATTENTION_NEEDED);
|
play_tone(AP_NOTIFY_PX4_TONE_LOUD_ATTENTION_NEEDED);
|
||||||
|
@ -56,7 +56,6 @@ private:
|
|||||||
uint8_t parachute_release : 1; // 1 if parachute is being released
|
uint8_t parachute_release : 1; // 1 if parachute is being released
|
||||||
uint8_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
uint8_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
||||||
uint8_t failsafe_radio : 1; // 1 if radio failsafe
|
uint8_t failsafe_radio : 1; // 1 if radio failsafe
|
||||||
uint8_t user_mode_initialized : 1; // 1 if the flight mode has changed or failed to be changed
|
|
||||||
} flags;
|
} flags;
|
||||||
|
|
||||||
int8_t _cont_tone_playing;
|
int8_t _cont_tone_playing;
|
||||||
|
Loading…
Reference in New Issue
Block a user