diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index d462d7c78c..f76934fb51 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -121,6 +121,7 @@ using matrix::wrap_2pi; #include "streams/HIL_ACTUATOR_CONTROLS.hpp" #include "streams/HIL_STATE_QUATERNION.hpp" #include "streams/HOME_POSITION.hpp" +#include "streams/LOCAL_POSITION_NED.hpp" #include "streams/MANUAL_CONTROL.hpp" #include "streams/MOUNT_ORIENTATION.hpp" #include "streams/NAV_CONTROLLER_OUTPUT.hpp" @@ -2720,74 +2721,6 @@ protected: } }; -class MavlinkStreamLocalPositionNED : public MavlinkStream -{ -public: - const char *get_name() const override - { - return MavlinkStreamLocalPositionNED::get_name_static(); - } - - static constexpr const char *get_name_static() - { - return "LOCAL_POSITION_NED"; - } - - static constexpr uint16_t get_id_static() - { - return MAVLINK_MSG_ID_LOCAL_POSITION_NED; - } - - uint16_t get_id() override - { - return get_id_static(); - } - - static MavlinkStream *new_instance(Mavlink *mavlink) - { - return new MavlinkStreamLocalPositionNED(mavlink); - } - - unsigned get_size() override - { - return _lpos_sub.advertised() ? MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0; - } - -private: - uORB::Subscription _lpos_sub{ORB_ID(vehicle_local_position)}; - - /* do not allow top copying this class */ - MavlinkStreamLocalPositionNED(MavlinkStreamLocalPositionNED &) = delete; - MavlinkStreamLocalPositionNED &operator = (const MavlinkStreamLocalPositionNED &) = delete; - -protected: - explicit MavlinkStreamLocalPositionNED(Mavlink *mavlink) : MavlinkStream(mavlink) - {} - - bool send() override - { - vehicle_local_position_s lpos; - - if (_lpos_sub.update(&lpos)) { - mavlink_local_position_ned_t msg{}; - - msg.time_boot_ms = lpos.timestamp / 1000; - msg.x = lpos.x; - msg.y = lpos.y; - msg.z = lpos.z; - msg.vx = lpos.vx; - msg.vy = lpos.vy; - msg.vz = lpos.vz; - - mavlink_msg_local_position_ned_send_struct(_mavlink->get_channel(), &msg); - - return true; - } - - return false; - } -}; - class MavlinkStreamCameraCapture : public MavlinkStream { public: @@ -2895,7 +2828,9 @@ static const StreamListItem streams_list[] = { create_stream_list_item(), create_stream_list_item(), create_stream_list_item(), +#if defined(LOCAL_POSITION_NED_HPP) create_stream_list_item(), +#endif // LOCAL_POSITION_NED_HPP create_stream_list_item(), #if defined(ESTIMATOR_STATUS_HPP) create_stream_list_item(), diff --git a/src/modules/mavlink/streams/LOCAL_POSITION_NED.hpp b/src/modules/mavlink/streams/LOCAL_POSITION_NED.hpp new file mode 100644 index 0000000000..8977999457 --- /dev/null +++ b/src/modules/mavlink/streams/LOCAL_POSITION_NED.hpp @@ -0,0 +1,86 @@ +/**************************************************************************** + * + * 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 LOCAL_POSITION_NED_HPP +#define LOCAL_POSITION_NED_HPP + +#include + +class MavlinkStreamLocalPositionNED : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamLocalPositionNED(mavlink); } + + static constexpr const char *get_name_static() { return "LOCAL_POSITION_NED"; } + static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_LOCAL_POSITION_NED; } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + return _lpos_sub.advertised() ? MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0; + } + +private: + explicit MavlinkStreamLocalPositionNED(Mavlink *mavlink) : MavlinkStream(mavlink) {} + + uORB::Subscription _lpos_sub{ORB_ID(vehicle_local_position)}; + + bool send() override + { + vehicle_local_position_s lpos; + + if (_lpos_sub.update(&lpos)) { + if (lpos.xy_valid && lpos.v_xy_valid) { + mavlink_local_position_ned_t msg{}; + + msg.time_boot_ms = lpos.timestamp / 1000; + msg.x = lpos.x; + msg.y = lpos.y; + msg.z = lpos.z; + msg.vx = lpos.vx; + msg.vy = lpos.vy; + msg.vz = lpos.vz; + + mavlink_msg_local_position_ned_send_struct(_mavlink->get_channel(), &msg); + + return true; + } + } + + return false; + } +}; + +#endif // LOCAL_POSITION_NED_HPP