From 248978b25ea4fa67e40b5762ef71ab9824a73a4f Mon Sep 17 00:00:00 2001 From: Daniel Agar <daniel@agar.ca> Date: Sat, 20 Feb 2021 15:04:56 -0500 Subject: [PATCH] mavlink: move SCALED_PRESSURE to separate stream header --- src/modules/mavlink/mavlink_messages.cpp | 161 ++---------------- .../mavlink/streams/SCALED_PRESSURE.hpp | 99 +++++++++++ .../mavlink/streams/SCALED_PRESSURE2.hpp | 99 +++++++++++ .../mavlink/streams/SCALED_PRESSURE3.hpp | 99 +++++++++++ 4 files changed, 309 insertions(+), 149 deletions(-) create mode 100644 src/modules/mavlink/streams/SCALED_PRESSURE.hpp create mode 100644 src/modules/mavlink/streams/SCALED_PRESSURE2.hpp create mode 100644 src/modules/mavlink/streams/SCALED_PRESSURE3.hpp diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 50a711a4ad..d6075f3483 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -131,6 +131,7 @@ using matrix::wrap_2pi; #include "streams/RAW_RPM.hpp" #include "streams/RC_CHANNELS.hpp" #include "streams/SCALED_IMU.hpp" +#include "streams/SCALED_PRESSURE.hpp" #include "streams/SERVO_OUTPUT_RAW.hpp" #include "streams/STATUSTEXT.hpp" #include "streams/STORAGE_INFORMATION.hpp" @@ -157,6 +158,8 @@ using matrix::wrap_2pi; # include "streams/LINK_NODE_STATUS.hpp" # include "streams/NAMED_VALUE_FLOAT.hpp" # include "streams/ODOMETRY.hpp" +# include "streams/SCALED_PRESSURE2.hpp" +# include "streams/SCALED_PRESSURE3.hpp" # include "streams/UTM_GLOBAL_POSITION.hpp" #endif // !CONSTRAINED_FLASH @@ -1067,152 +1070,6 @@ protected: } }; -template <int N, typename Derived> -class MavlinkStreamScaledPressureBase : public MavlinkStream -{ -public: - const char *get_name() const override - { - return Derived::get_name_static(); - } - - uint16_t get_id() override - { - return Derived::get_id_static(); - } - - static MavlinkStream *new_instance(Mavlink *mavlink) - { - return new Derived(mavlink); - } - -private: - uORB::Subscription _differential_pressure_sub{ORB_ID(differential_pressure)}; - uORB::Subscription _sensor_baro_sub{ORB_ID(sensor_baro), N}; - - /* do not allow top copying this class */ - MavlinkStreamScaledPressureBase(MavlinkStreamScaledPressureBase &) = delete; - MavlinkStreamScaledPressureBase &operator = (const MavlinkStreamScaledPressureBase &) = delete; - -protected: - explicit MavlinkStreamScaledPressureBase(Mavlink *mavlink) : MavlinkStream(mavlink) - {} - - bool send() override - { - if (_sensor_baro_sub.updated() || _differential_pressure_sub.updated()) { - sensor_baro_s sensor_baro{}; - differential_pressure_s differential_pressure{}; - _sensor_baro_sub.copy(&sensor_baro); - _differential_pressure_sub.copy(&differential_pressure); - - typename Derived::mav_msg_type msg{}; - msg.time_boot_ms = sensor_baro.timestamp / 1000; - msg.press_abs = sensor_baro.pressure; - msg.press_diff = differential_pressure.differential_pressure_raw_pa; - msg.temperature = sensor_baro.temperature; - - Derived::send(_mavlink->get_channel(), &msg); - - return true; - } - - return false; - } -}; - -template <int N> class MavlinkStreamScaledPressure {}; - -template <> -class MavlinkStreamScaledPressure<0> : public MavlinkStreamScaledPressureBase<0, MavlinkStreamScaledPressure<0> > -{ -public: - typedef MavlinkStreamScaledPressureBase<0, MavlinkStreamScaledPressure<0> > Base; - typedef mavlink_scaled_pressure_t mav_msg_type; - - explicit MavlinkStreamScaledPressure(Mavlink *mavlink) : Base(mavlink) {} - - static void send(mavlink_channel_t channel, const MavlinkStreamScaledPressure<0>::mav_msg_type *msg) - { - mavlink_msg_scaled_pressure_send_struct(channel, msg); - } - - static const char *get_name_static() - { - return "SCALED_PRESSURE"; - } - - static uint16_t get_id_static() - { - return MAVLINK_MSG_ID_SCALED_PRESSURE; - } - - unsigned get_size() override - { - return MAVLINK_MSG_ID_SCALED_PRESSURE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; - } -}; - -template <> -class MavlinkStreamScaledPressure<1> : public MavlinkStreamScaledPressureBase<1, MavlinkStreamScaledPressure<1> > -{ -public: - typedef MavlinkStreamScaledPressureBase<1, MavlinkStreamScaledPressure<1> > Base; - typedef mavlink_scaled_pressure2_t mav_msg_type; - - explicit MavlinkStreamScaledPressure(Mavlink *mavlink) : Base(mavlink) {} - - static void send(mavlink_channel_t channel, const MavlinkStreamScaledPressure<1>::mav_msg_type *msg) - { - mavlink_msg_scaled_pressure2_send_struct(channel, msg); - } - - static const char *get_name_static() - { - return "SCALED_PRESSURE2"; - } - - static uint16_t get_id_static() - { - return MAVLINK_MSG_ID_SCALED_PRESSURE2; - } - - unsigned get_size() override - { - return MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; - } -}; - -template <> -class MavlinkStreamScaledPressure<2> : public MavlinkStreamScaledPressureBase<2, MavlinkStreamScaledPressure<2> > -{ -public: - typedef MavlinkStreamScaledPressureBase<2, MavlinkStreamScaledPressure<2> > Base; - typedef mavlink_scaled_pressure3_t mav_msg_type; - - explicit MavlinkStreamScaledPressure(Mavlink *mavlink) : Base(mavlink) {} - - static void send(mavlink_channel_t channel, const MavlinkStreamScaledPressure<2>::mav_msg_type *msg) - { - mavlink_msg_scaled_pressure3_send_struct(channel, msg); - } - - static const char *get_name_static() - { - return "SCALED_PRESSURE3"; - } - - static uint16_t get_id_static() - { - return MAVLINK_MSG_ID_SCALED_PRESSURE3; - } - - unsigned get_size() override - { - return MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; - } -}; - class MavlinkStreamCameraTrigger : public MavlinkStream { public: @@ -1409,9 +1266,15 @@ static const StreamListItem streams_list[] = { create_stream_list_item<MavlinkStreamScaledIMU<1> >(), create_stream_list_item<MavlinkStreamScaledIMU<2> >(), #endif // SCALED_IMU_HPP - create_stream_list_item<MavlinkStreamScaledPressure<0> >(), - // create_stream_list_item<MavlinkStreamScaledPressure<1> >(), - // create_stream_list_item<MavlinkStreamScaledPressure<2> >(), +#if defined(SCALED_PRESSURE) + create_stream_list_item<MavlinkStreamScaledPressure>(), +#endif // SCALED_PRESSURE +#if defined(SCALED_PRESSURE2) + create_stream_list_item<MavlinkStreamScaledPressure2>(), +#endif // SCALED_PRESSURE2 +#if defined(SCALED_PRESSURE3) + create_stream_list_item<MavlinkStreamScaledPressure3>(), +#endif // SCALED_PRESSURE3 #if defined(ACTUATOR_OUTPUT_STATUS_HPP) create_stream_list_item<MavlinkStreamActuatorOutputStatus>(), #endif // ACTUATOR_OUTPUT_STATUS_HPP diff --git a/src/modules/mavlink/streams/SCALED_PRESSURE.hpp b/src/modules/mavlink/streams/SCALED_PRESSURE.hpp new file mode 100644 index 0000000000..3e7263f3aa --- /dev/null +++ b/src/modules/mavlink/streams/SCALED_PRESSURE.hpp @@ -0,0 +1,99 @@ +/**************************************************************************** + * + * Copyright (c) 2021 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. + * + ****************************************************************************/ + +#ifndef SCALED_PRESSURE_HPP +#define SCALED_PRESSURE_HPP + +#include <uORB/topics/differential_pressure.h> +#include <uORB/topics/sensor_baro.h> + +class MavlinkStreamScaledPressure : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamScaledPressure(mavlink); } + + static constexpr const char *get_name_static() { return "SCALED_PRESSURE"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_SCALED_PRESSURE; } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + if (_sensor_baro_sub.advertised() || _differential_pressure_sub.advertised()) { + return MAVLINK_MSG_ID_SCALED_PRESSURE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + + return 0; + } + +private: + explicit MavlinkStreamScaledPressure(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::Subscription _differential_pressure_sub{ORB_ID(differential_pressure), 0}; + uORB::Subscription _sensor_baro_sub{ORB_ID(sensor_baro), 0}; + + bool send() override + { + if (_sensor_baro_sub.updated() || _differential_pressure_sub.updated()) { + mavlink_scaled_pressure_t msg{}; + + sensor_baro_s sensor_baro; + + if (_sensor_baro_sub.copy(&sensor_baro)) { + msg.time_boot_ms = sensor_baro.timestamp / 1000; + msg.press_abs = sensor_baro.pressure; // millibar to hPa + msg.temperature = roundf(sensor_baro.temperature * 100.f); // centidegrees + } + + differential_pressure_s differential_pressure; + + if (_differential_pressure_sub.copy(&differential_pressure)) { + if (msg.time_boot_ms == 0) { + msg.time_boot_ms = differential_pressure.timestamp / 1000; + } + + msg.press_diff = differential_pressure.differential_pressure_raw_pa * 100.f; // Pa to hPa + msg.temperature_press_diff = roundf(differential_pressure.temperature * 100.f); // centidegrees + } + + mavlink_msg_scaled_pressure_send_struct(_mavlink->get_channel(), &msg); + + return true; + } + + return false; + } +}; + +#endif // SCALED_PRESSURE_HPP diff --git a/src/modules/mavlink/streams/SCALED_PRESSURE2.hpp b/src/modules/mavlink/streams/SCALED_PRESSURE2.hpp new file mode 100644 index 0000000000..e49a17e992 --- /dev/null +++ b/src/modules/mavlink/streams/SCALED_PRESSURE2.hpp @@ -0,0 +1,99 @@ +/**************************************************************************** + * + * Copyright (c) 2021 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. + * + ****************************************************************************/ + +#ifndef SCALED_PRESSURE2_HPP +#define SCALED_PRESSURE2_HPP + +#include <uORB/topics/differential_pressure.h> +#include <uORB/topics/sensor_baro.h> + +class MavlinkStreamScaledPressure2 : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamScaledPressure2(mavlink); } + + static constexpr const char *get_name_static() { return "SCALED_PRESSURE2"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_SCALED_PRESSURE2; } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + if (_sensor_baro_sub.advertised() || _differential_pressure_sub.advertised()) { + return MAVLINK_MSG_ID_SCALED_PRESSURE2_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + + return 0; + } + +private: + explicit MavlinkStreamScaledPressure2(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::Subscription _differential_pressure_sub{ORB_ID(differential_pressure), 1}; + uORB::Subscription _sensor_baro_sub{ORB_ID(sensor_baro), 1}; + + bool send() override + { + if (_sensor_baro_sub.updated() || _differential_pressure_sub.updated()) { + mavlink_scaled_pressure2_t msg{}; + + sensor_baro_s sensor_baro; + + if (_sensor_baro_sub.copy(&sensor_baro)) { + msg.time_boot_ms = sensor_baro.timestamp / 1000; + msg.press_abs = sensor_baro.pressure; // millibar to hPa + msg.temperature = roundf(sensor_baro.temperature * 100.f); // centidegrees + } + + differential_pressure_s differential_pressure; + + if (_differential_pressure_sub.copy(&differential_pressure)) { + if (msg.time_boot_ms == 0) { + msg.time_boot_ms = differential_pressure.timestamp / 1000; + } + + msg.press_diff = differential_pressure.differential_pressure_raw_pa * 100.f; // Pa to hPa + msg.temperature_press_diff = roundf(differential_pressure.temperature * 100.f); // centidegrees + } + + mavlink_msg_scaled_pressure2_send_struct(_mavlink->get_channel(), &msg); + + return true; + } + + return false; + } +}; + +#endif // SCALED_PRESSURE2_HPP diff --git a/src/modules/mavlink/streams/SCALED_PRESSURE3.hpp b/src/modules/mavlink/streams/SCALED_PRESSURE3.hpp new file mode 100644 index 0000000000..f3fe6603f0 --- /dev/null +++ b/src/modules/mavlink/streams/SCALED_PRESSURE3.hpp @@ -0,0 +1,99 @@ +/**************************************************************************** + * + * Copyright (c) 2021 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. + * + ****************************************************************************/ + +#ifndef SCALED_PRESSURE3_HPP +#define SCALED_PRESSURE3_HPP + +#include <uORB/topics/differential_pressure.h> +#include <uORB/topics/sensor_baro.h> + +class MavlinkStreamScaledPressure3 : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamScaledPressure3(mavlink); } + + static constexpr const char *get_name_static() { return "SCALED_PRESSURE3"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_SCALED_PRESSURE3; } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + if (_sensor_baro_sub.advertised() || _differential_pressure_sub.advertised()) { + return MAVLINK_MSG_ID_SCALED_PRESSURE3_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + + return 0; + } + +private: + explicit MavlinkStreamScaledPressure3(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::Subscription _differential_pressure_sub{ORB_ID(differential_pressure), 2}; + uORB::Subscription _sensor_baro_sub{ORB_ID(sensor_baro), 2}; + + bool send() override + { + if (_sensor_baro_sub.updated() || _differential_pressure_sub.updated()) { + mavlink_scaled_pressure3_t msg{}; + + sensor_baro_s sensor_baro; + + if (_sensor_baro_sub.copy(&sensor_baro)) { + msg.time_boot_ms = sensor_baro.timestamp / 1000; + msg.press_abs = sensor_baro.pressure; // millibar to hPa + msg.temperature = roundf(sensor_baro.temperature * 100.f); // centidegrees + } + + differential_pressure_s differential_pressure; + + if (_differential_pressure_sub.copy(&differential_pressure)) { + if (msg.time_boot_ms == 0) { + msg.time_boot_ms = differential_pressure.timestamp / 1000; + } + + msg.press_diff = differential_pressure.differential_pressure_raw_pa * 100.f; // Pa to hPa + msg.temperature_press_diff = roundf(differential_pressure.temperature * 100.f); // centidegrees + } + + mavlink_msg_scaled_pressure3_send_struct(_mavlink->get_channel(), &msg); + + return true; + } + + return false; + } +}; + +#endif // SCALED_PRESSURE3_HPP