Browse Source

AP_Notify: added handling of PLAY_TUNE message

master
Andrew Tridgell 9 years ago
parent
commit
7fe1c58575
  1. 8
      libraries/AP_Notify/AP_Notify.cpp
  2. 3
      libraries/AP_Notify/AP_Notify.h
  3. 4
      libraries/AP_Notify/NotifyDevice.h
  4. 15
      libraries/AP_Notify/ToneAlarm_PX4.cpp
  5. 3
      libraries/AP_Notify/ToneAlarm_PX4.h

8
libraries/AP_Notify/AP_Notify.cpp

@ -171,3 +171,11 @@ void AP_Notify::handle_led_control(mavlink_message_t *msg) @@ -171,3 +171,11 @@ void AP_Notify::handle_led_control(mavlink_message_t *msg)
_devices[i]->handle_led_control(msg);
}
}
// handle a PLAY_TUNE message
void AP_Notify::handle_play_tune(mavlink_message_t *msg)
{
for (uint8_t i = 0; i < CONFIG_NOTIFY_DEVICES_COUNT; i++) {
_devices[i]->handle_play_tune(msg);
}
}

3
libraries/AP_Notify/AP_Notify.h

@ -107,6 +107,9 @@ public: @@ -107,6 +107,9 @@ public:
// handle a LED_CONTROL message
static void handle_led_control(mavlink_message_t* msg);
// handle a PLAY_TUNE message
static void handle_play_tune(mavlink_message_t* msg);
static const struct AP_Param::GroupInfo var_info[];
bool buzzer_enabled() const { return _buzzer_enable; }

4
libraries/AP_Notify/NotifyDevice.h

@ -13,9 +13,13 @@ public: @@ -13,9 +13,13 @@ public:
// update - updates device according to timed_updated. Should be
// called at 50Hz
virtual void update() = 0;
// handle a LED_CONTROL message, by default device ignore message
virtual void handle_led_control(mavlink_message_t *msg) {}
// handle a PLAY_TUNE message, by default device ignore message
virtual void handle_play_tune(mavlink_message_t *msg) {}
// this pointer is used to read the parameters relative to devices
const AP_Notify *pNotify;
};

15
libraries/AP_Notify/ToneAlarm_PX4.cpp

@ -336,4 +336,19 @@ void ToneAlarm_PX4::update() @@ -336,4 +336,19 @@ void ToneAlarm_PX4::update()
}
}
/*
handle a PLAY_TUNE message
*/
void ToneAlarm_PX4::handle_play_tune(mavlink_message_t *msg)
{
// decode mavlink message
mavlink_play_tune_t packet;
mavlink_msg_play_tune_decode(msg, &packet);
play_string(packet.tune);
}
#endif // CONFIG_HAL_BOARD == HAL_BOARD_PX4

3
libraries/AP_Notify/ToneAlarm_PX4.h

@ -31,6 +31,9 @@ public: @@ -31,6 +31,9 @@ public:
/// update - updates led according to timed_updated. Should be called at 50Hz
void update();
// handle a PLAY_TUNE message
void handle_play_tune(mavlink_message_t *msg);
private:
/// play_tune - play one of the pre-defined tunes
void play_tone(const uint8_t tone_index);

Loading…
Cancel
Save