diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index 9ba0882c6de5..80df1227a445 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -58,6 +58,7 @@ px4_add_module( mavlink_stream.cpp mavlink_ulog.cpp mavlink_timesync.cpp + tune_publisher.cpp MODULE_CONFIG module.yaml DEPENDS diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 423a24686602..580b4fe777d4 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -82,6 +82,7 @@ using matrix::wrap_2pi; MavlinkReceiver::~MavlinkReceiver() { + delete _tune_publisher; delete _px4_accel; delete _px4_baro; delete _px4_gyro; @@ -237,6 +238,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_play_tune(msg); break; + case MAVLINK_MSG_ID_PLAY_TUNE_V2: + handle_message_play_tune_v2(msg); + break; + case MAVLINK_MSG_ID_OBSTACLE_DISTANCE: handle_message_obstacle_distance(msg); break; @@ -1758,24 +1763,58 @@ MavlinkReceiver::handle_message_play_tune(mavlink_message_t *msg) mavlink_play_tune_t play_tune; mavlink_msg_play_tune_decode(msg, &play_tune); - char *tune = play_tune.tune; + if ((mavlink_system.sysid == play_tune.target_system || play_tune.target_system == 0) && + (mavlink_system.compid == play_tune.target_component || play_tune.target_component == 0)) { - if ((mavlink_system.sysid == play_tune.target_system || - play_tune.target_system == 0) && - (mavlink_system.compid == play_tune.target_component || - play_tune.target_component == 0)) { + // Let's make sure the input is 0 terminated, so we don't ever overrun it. + play_tune.tune2[sizeof(play_tune.tune2) - 1] = '\0'; - if (*tune == 'M') { - int fd = px4_open(TONE_ALARM0_DEVICE_PATH, PX4_F_WRONLY); + schedule_tune(play_tune.tune); + } +} - if (fd >= 0) { - px4_write(fd, tune, strlen(tune) + 1); - px4_close(fd); - } +void +MavlinkReceiver::handle_message_play_tune_v2(mavlink_message_t *msg) +{ + mavlink_play_tune_v2_t play_tune_v2; + mavlink_msg_play_tune_v2_decode(msg, &play_tune_v2); + + if ((mavlink_system.sysid == play_tune_v2.target_system || play_tune_v2.target_system == 0) && + (mavlink_system.compid == play_tune_v2.target_component || play_tune_v2.target_component == 0)) { + + if (play_tune_v2.format != TUNE_FORMAT_QBASIC1_1) { + PX4_ERR("Tune format %d not supported", play_tune_v2.format); + return; } + + // Let's make sure the input is 0 terminated, so we don't ever overrun it. + play_tune_v2.tune[sizeof(play_tune_v2.tune) - 1] = '\0'; + + schedule_tune(play_tune_v2.tune); } } +void MavlinkReceiver::schedule_tune(const char *tune) +{ + // We only allocate the TunePublisher object if we ever use it but we + // don't remove it to avoid fragmentation over time. + if (_tune_publisher == nullptr) { + _tune_publisher = new TunePublisher(); + + if (_tune_publisher == nullptr) { + PX4_ERR("Could not allocate tune publisher"); + return; + } + } + + const hrt_abstime now = hrt_absolute_time(); + + _tune_publisher->set_tune_string(tune, now); + // Send first one straightaway. + _tune_publisher->publish_next_tune(now); +} + + void MavlinkReceiver::handle_message_obstacle_distance(mavlink_message_t *msg) { @@ -2923,6 +2962,9 @@ MavlinkReceiver::Run() last_send_update = t; } + if (_tune_publisher != nullptr) { + _tune_publisher->publish_next_tune(t); + } } } diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 7c55679e9c5e..8d803e799f03 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012-2019 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-2020 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -46,6 +46,7 @@ #include "mavlink_mission.h" #include "mavlink_parameters.h" #include "mavlink_timesync.h" +#include "tune_publisher.h" #include #include @@ -85,6 +86,7 @@ #include #include #include +#include #include #include #include @@ -158,6 +160,7 @@ class MavlinkReceiver : public ModuleParams void handle_message_optical_flow_rad(mavlink_message_t *msg); void handle_message_ping(mavlink_message_t *msg); void handle_message_play_tune(mavlink_message_t *msg); + void handle_message_play_tune_v2(mavlink_message_t *msg); void handle_message_radio_status(mavlink_message_t *msg); void handle_message_rc_channels_override(mavlink_message_t *msg); void handle_message_serial_control(mavlink_message_t *msg); @@ -206,6 +209,8 @@ class MavlinkReceiver : public ModuleParams void fill_thrust(float *thrust_body_array, uint8_t vehicle_type, float thrust); + void schedule_tune(const char *tune); + /** * @brief Updates the battery, optical flow, and flight ID subscribed parameters. */ @@ -293,6 +298,9 @@ class MavlinkReceiver : public ModuleParams hrt_abstime _last_utm_global_pos_com{0}; + // Allocated if needed. + TunePublisher *_tune_publisher{nullptr}; + DEFINE_PARAMETERS( (ParamFloat) _param_bat_crit_thr, (ParamFloat) _param_bat_emergen_thr, diff --git a/src/modules/mavlink/tune_publisher.cpp b/src/modules/mavlink/tune_publisher.cpp new file mode 100644 index 000000000000..2e6bb29eb4ef --- /dev/null +++ b/src/modules/mavlink/tune_publisher.cpp @@ -0,0 +1,94 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + + +#include "tune_publisher.h" +#include "string.h" +#include + +void TunePublisher::set_tune_string(const char *tune, const hrt_abstime &now) +{ + // The tune string needs to be 0 terminated. + const unsigned tune_len = strlen(tune); + + // We don't expect the tune string to be longer than what can come in via MAVLink including 0 termination. + if (tune_len >= MAX_TUNE_LEN) { + PX4_ERR("Tune string too long."); + return; + } + + strncpy(_tune_buffer, tune, MAX_TUNE_LEN); + + _tunes.set_string(_tune_buffer, tune_control_s::VOLUME_LEVEL_DEFAULT); + + _next_publish_time = now; +} + + +void TunePublisher::publish_next_tune(const hrt_abstime now) +{ + if (_next_publish_time == 0) { + // Nothing to play. + return; + } + + if (now < _next_publish_time) { + // Too early, try again later. + return; + } + + unsigned frequency; + unsigned duration; + unsigned silence; + uint8_t volume; + + if (_tunes.get_next_note(frequency, duration, silence, volume) > 0) { + tune_control_s tune_control {}; + tune_control.tune_id = 0; + tune_control.volume = tune_control_s::VOLUME_LEVEL_DEFAULT; + + tune_control.tune_id = 0; + tune_control.frequency = static_cast(frequency); + tune_control.duration = static_cast(duration); + tune_control.silence = static_cast(silence); + tune_control.volume = static_cast(volume); + tune_control.timestamp = now; + _tune_control_pub.publish(tune_control); + + _next_publish_time = now + duration + silence; + + } else { + // We're done, let's reset. + _next_publish_time = 0; + } +} diff --git a/src/modules/mavlink/tune_publisher.h b/src/modules/mavlink/tune_publisher.h new file mode 100644 index 000000000000..42095e0da735 --- /dev/null +++ b/src/modules/mavlink/tune_publisher.h @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * Copyright (c) 2020 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include +#include +#include + + +class TunePublisher +{ +public: + void set_tune_string(const char *tune, const hrt_abstime &now); + void publish_next_tune(const hrt_abstime now); + +private: + static constexpr unsigned MAX_TUNE_LEN {248}; + + Tunes _tunes {}; + char _tune_buffer[MAX_TUNE_LEN] {0}; + hrt_abstime _next_publish_time {0}; + + uORB::PublicationQueued _tune_control_pub{ORB_ID(tune_control)}; +};