mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Notify: add parachute release tune for Pixhawk
This commit is contained in:
parent
47c1cb8b99
commit
e3e7fc284d
@ -43,6 +43,7 @@ public:
|
||||
uint16_t failsafe_battery : 1; // 1 if battery failsafe
|
||||
uint16_t failsafe_gps : 1; // 1 if gps failsafe
|
||||
uint16_t arming_failed : 1; // 1 if copter failed to arm after user input
|
||||
uint16_t parachute_release : 1; // 1 if parachute is being released
|
||||
|
||||
// additional flags
|
||||
uint16_t external_leds : 1; // 1 if external LEDs are enabled (normally only used for copter)
|
||||
|
@ -64,7 +64,8 @@ void ToneAlarm_PX4::update()
|
||||
if (_tonealarm_fd == -1) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
// check for arming failure
|
||||
if(flags.arming_failed != AP_Notify::flags.arming_failed) {
|
||||
flags.arming_failed = AP_Notify::flags.arming_failed;
|
||||
if(flags.arming_failed) {
|
||||
@ -110,6 +111,15 @@ void ToneAlarm_PX4::update()
|
||||
play_tune(TONE_GPS_WARNING_TUNE);
|
||||
}
|
||||
}
|
||||
|
||||
// check parachute release
|
||||
if (flags.parachute_release != AP_Notify::flags.parachute_release) {
|
||||
flags.parachute_release = AP_Notify::flags.parachute_release;
|
||||
if (flags.parachute_release) {
|
||||
// parachute release warning tune
|
||||
play_tune(TONE_PARACHUTE_RELEASE_TUNE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||
|
@ -42,6 +42,7 @@ private:
|
||||
uint8_t gps_glitching : 1; // 1 if gps position is not good
|
||||
uint8_t failsafe_gps : 1; // 1 if gps failsafe
|
||||
uint8_t arming_failed : 1; // 0 = failing checks, 1 = passed
|
||||
uint8_t parachute_release : 1; // 1 if parachute is being released
|
||||
} flags;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user