mirror of https://github.com/ArduPilot/ardupilot
AP_Notify: process mavlink play_tune in frontend
This commit is contained in:
parent
59b5a6e604
commit
f846f703e4
|
@ -442,16 +442,6 @@ void AP_Notify::handle_rgb_id(uint8_t r, uint8_t g, uint8_t b, uint8_t id)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// handle a PLAY_TUNE message
|
|
||||||
void AP_Notify::handle_play_tune(const mavlink_message_t &msg)
|
|
||||||
{
|
|
||||||
for (uint8_t i = 0; i < _num_devices; i++) {
|
|
||||||
if (_devices[i] != nullptr) {
|
|
||||||
_devices[i]->handle_play_tune(msg);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void AP_Notify::play_tune(const char *tune)
|
void AP_Notify::play_tune(const char *tune)
|
||||||
{
|
{
|
||||||
for (uint8_t i = 0; i < _num_devices; i++) {
|
for (uint8_t i = 0; i < _num_devices; i++) {
|
||||||
|
|
|
@ -16,7 +16,7 @@
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_Param/AP_Param.h>
|
#include <AP_Param/AP_Param.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
#include "AP_Notify_config.h"
|
||||||
|
|
||||||
#include "NotifyDevice.h"
|
#include "NotifyDevice.h"
|
||||||
|
|
||||||
|
@ -160,8 +160,10 @@ public:
|
||||||
// handle RGB from Scripting
|
// handle RGB from Scripting
|
||||||
static void handle_rgb_id(uint8_t r, uint8_t g, uint8_t b, uint8_t id);
|
static void handle_rgb_id(uint8_t r, uint8_t g, uint8_t b, uint8_t id);
|
||||||
|
|
||||||
|
#if AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED
|
||||||
// handle a PLAY_TUNE message
|
// handle a PLAY_TUNE message
|
||||||
static void handle_play_tune(const mavlink_message_t &msg);
|
static void handle_play_tune(const mavlink_message_t &msg);
|
||||||
|
#endif
|
||||||
|
|
||||||
// play a tune string
|
// play a tune string
|
||||||
static void play_tune(const char *tune);
|
static void play_tune(const char *tune);
|
||||||
|
|
|
@ -0,0 +1,10 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <GCS_MAVLink/GCS_config.h>
|
||||||
|
#if HAL_GCS_ENABLED
|
||||||
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED
|
||||||
|
#define AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED HAL_GCS_ENABLED
|
||||||
|
#endif
|
|
@ -1,7 +1,7 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
#include "AP_Notify_config.h"
|
||||||
|
|
||||||
class AP_Notify;
|
class AP_Notify;
|
||||||
|
|
||||||
|
@ -17,9 +17,6 @@ public:
|
||||||
// handle a LED_CONTROL message, by default device ignore message
|
// handle a LED_CONTROL message, by default device ignore message
|
||||||
virtual void handle_led_control(const mavlink_message_t &msg) {}
|
virtual void handle_led_control(const mavlink_message_t &msg) {}
|
||||||
|
|
||||||
// handle a PLAY_TUNE message, by default device ignore message
|
|
||||||
virtual void handle_play_tune(const mavlink_message_t &msg) {}
|
|
||||||
|
|
||||||
// play a MML tune
|
// play a MML tune
|
||||||
virtual void play_tune(const char *tune) {}
|
virtual void play_tune(const char *tune) {}
|
||||||
|
|
||||||
|
|
|
@ -449,26 +449,25 @@ void AP_ToneAlarm::update()
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#if AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED
|
||||||
/*
|
/*
|
||||||
* handle a PLAY_TUNE message
|
* handle a PLAY_TUNE message
|
||||||
*/
|
*/
|
||||||
void AP_ToneAlarm::handle_play_tune(const mavlink_message_t &msg)
|
void AP_Notify::handle_play_tune(const mavlink_message_t &msg)
|
||||||
{
|
{
|
||||||
// decode mavlink message
|
// decode mavlink message
|
||||||
mavlink_play_tune_t packet;
|
mavlink_play_tune_t packet;
|
||||||
|
|
||||||
mavlink_msg_play_tune_decode(&msg, &packet);
|
mavlink_msg_play_tune_decode(&msg, &packet);
|
||||||
|
|
||||||
WITH_SEMAPHORE(_sem);
|
char _tone_buf[AP_NOTIFY_TONEALARM_TONE_BUF_SIZE] {}; // ~100 bytes
|
||||||
|
|
||||||
_mml_player.stop();
|
|
||||||
|
|
||||||
strncpy(_tone_buf, packet.tune, MIN(sizeof(packet.tune), sizeof(_tone_buf)-1));
|
strncpy(_tone_buf, packet.tune, MIN(sizeof(packet.tune), sizeof(_tone_buf)-1));
|
||||||
_tone_buf[sizeof(_tone_buf)-1] = 0;
|
|
||||||
uint8_t len = strlen(_tone_buf);
|
uint8_t len = strlen(_tone_buf);
|
||||||
uint8_t len2 = strnlen(packet.tune2, sizeof(packet.tune2));
|
uint8_t len2 = strnlen(packet.tune2, sizeof(packet.tune2));
|
||||||
len2 = MIN((sizeof(_tone_buf)-1)-len, len2);
|
len2 = MIN((sizeof(_tone_buf)-1)-len, len2);
|
||||||
strncpy(_tone_buf+len, packet.tune2, len2);
|
memcpy(_tone_buf+len, packet.tune2, len2); // not strncpy to avoid truncation warning
|
||||||
_tone_buf[sizeof(_tone_buf)-1] = 0;
|
_tone_buf[sizeof(_tone_buf)-1] = 0;
|
||||||
_mml_player.play(_tone_buf);
|
|
||||||
|
play_tune(_tone_buf);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -32,9 +32,6 @@ public:
|
||||||
/// update - updates led according to timed_updated. Should be called at 50Hz
|
/// update - updates led according to timed_updated. Should be called at 50Hz
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
// handle a PLAY_TUNE message
|
|
||||||
void handle_play_tune(const mavlink_message_t &msg) override;
|
|
||||||
|
|
||||||
// play_tune - play tone specified by the provided string of notes
|
// play_tune - play tone specified by the provided string of notes
|
||||||
void play_tune(const char *tune) override;
|
void play_tune(const char *tune) override;
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue