From e3e7fc284dd8db6946a07d7051405c9673b631c9 Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Thu, 3 Apr 2014 22:03:12 +0900 Subject: [PATCH] Notify: add parachute release tune for Pixhawk --- libraries/AP_Notify/AP_Notify.h | 1 + libraries/AP_Notify/ToneAlarm_PX4.cpp | 12 +++++++++++- libraries/AP_Notify/ToneAlarm_PX4.h | 1 + 3 files changed, 13 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Notify/AP_Notify.h b/libraries/AP_Notify/AP_Notify.h index 5c76e0425..70cbf07aa 100644 --- a/libraries/AP_Notify/AP_Notify.h +++ b/libraries/AP_Notify/AP_Notify.h @@ -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) diff --git a/libraries/AP_Notify/ToneAlarm_PX4.cpp b/libraries/AP_Notify/ToneAlarm_PX4.cpp index 4f860180f..17e39c012 100644 --- a/libraries/AP_Notify/ToneAlarm_PX4.cpp +++ b/libraries/AP_Notify/ToneAlarm_PX4.cpp @@ -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 diff --git a/libraries/AP_Notify/ToneAlarm_PX4.h b/libraries/AP_Notify/ToneAlarm_PX4.h index 2a353898f..ac5514424 100644 --- a/libraries/AP_Notify/ToneAlarm_PX4.h +++ b/libraries/AP_Notify/ToneAlarm_PX4.h @@ -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; }; -- GitLab