Browse Source

AP_Notify: added tones for tuning stages

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
9cd4f8a856
  1. 3
      libraries/AP_Notify/AP_Notify.h
  2. 13
      libraries/AP_Notify/ToneAlarm_PX4.cpp

3
libraries/AP_Notify/AP_Notify.h

@ -87,6 +87,9 @@ public: @@ -87,6 +87,9 @@ public:
uint16_t compass_cal_saved : 1; // 1 when compass calibration was just saved
uint16_t compass_cal_failed : 1; // 1 when compass calibration has just failed
uint16_t compass_cal_canceled : 1; // 1 when compass calibration was just canceled
uint16_t tune_started : 1; // tuning a parameter has started
uint16_t tune_next : 1; // tuning switched to next parameter
uint16_t tune_save : 1; // tuning saved parameters
};
// the notify flags are static to allow direct class access

13
libraries/AP_Notify/ToneAlarm_PX4.cpp

@ -296,6 +296,19 @@ void ToneAlarm_PX4::update() @@ -296,6 +296,19 @@ void ToneAlarm_PX4::update()
stop_cont_tone();
}
}
if (AP_Notify::events.tune_started) {
play_tone(AP_NOTIFY_PX4_TONE_LOUD_NEU_FEEDBACK);
AP_Notify::events.tune_started = 0;
}
if (AP_Notify::events.tune_next) {
play_tone(AP_NOTIFY_PX4_TONE_LOUD_POS_FEEDBACK);
AP_Notify::events.tune_next = 0;
}
if (AP_Notify::events.tune_save) {
play_tone(AP_NOTIFY_PX4_TONE_QUIET_READY_OR_FINISHED);
AP_Notify::events.tune_save = 0;
}
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4

Loading…
Cancel
Save