AP_Notify: added handling of PLAY_TUNE message
This commit is contained in:
parent
c93ba0dcc6
commit
7fe1c58575
@ -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);
|
||||
}
|
||||
}
|
||||
|
@ -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; }
|
||||
|
@ -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;
|
||||
};
|
||||
|
@ -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
|
||||
|
@ -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…
Reference in New Issue
Block a user