diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 8f2c8b5099..07e66e587e 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -106,6 +106,7 @@ using matrix::Vector3f; using matrix::wrap_2pi; #include "streams/ALTITUDE.hpp" +#include "streams/ATTITUDE.hpp" #include "streams/AUTOPILOT_VERSION.hpp" #include "streams/DISTANCE_SENSOR.hpp" #include "streams/ESC_INFO.hpp" @@ -1432,83 +1433,6 @@ protected: } }; - -class MavlinkStreamAttitude : public MavlinkStream -{ -public: - const char *get_name() const override - { - return MavlinkStreamAttitude::get_name_static(); - } - - static constexpr const char *get_name_static() - { - return "ATTITUDE"; - } - - static constexpr uint16_t get_id_static() - { - return MAVLINK_MSG_ID_ATTITUDE; - } - - uint16_t get_id() override - { - return get_id_static(); - } - - static MavlinkStream *new_instance(Mavlink *mavlink) - { - return new MavlinkStreamAttitude(mavlink); - } - - unsigned get_size() override - { - return _att_sub.advertised() ? MAVLINK_MSG_ID_ATTITUDE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0; - } - -private: - uORB::Subscription _att_sub{ORB_ID(vehicle_attitude)}; - uORB::Subscription _angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; - - /* do not allow top copying this class */ - MavlinkStreamAttitude(MavlinkStreamAttitude &) = delete; - MavlinkStreamAttitude &operator = (const MavlinkStreamAttitude &) = delete; - - -protected: - explicit MavlinkStreamAttitude(Mavlink *mavlink) : MavlinkStream(mavlink) - {} - - bool send() override - { - vehicle_attitude_s att; - - if (_att_sub.update(&att)) { - vehicle_angular_velocity_s angular_velocity{}; - _angular_velocity_sub.copy(&angular_velocity); - - mavlink_attitude_t msg{}; - - const matrix::Eulerf euler = matrix::Quatf(att.q); - msg.time_boot_ms = att.timestamp / 1000; - msg.roll = euler.phi(); - msg.pitch = euler.theta(); - msg.yaw = euler.psi(); - - msg.rollspeed = angular_velocity.xyz[0]; - msg.pitchspeed = angular_velocity.xyz[1]; - msg.yawspeed = angular_velocity.xyz[2]; - - mavlink_msg_attitude_send_struct(_mavlink->get_channel(), &msg); - - return true; - } - - return false; - } -}; - - class MavlinkStreamAttitudeQuaternion : public MavlinkStream { public: @@ -4225,7 +4149,9 @@ static const StreamListItem streams_list[] = { create_stream_list_item >(), // create_stream_list_item >(), // create_stream_list_item >(), +#if defined(ATTITUDE_HPP) create_stream_list_item(), +#endif // ATTITUDE_HPP create_stream_list_item(), create_stream_list_item(), #if defined(GPS_GLOBAL_ORIGIN_HPP) diff --git a/src/modules/mavlink/streams/ATTITUDE.hpp b/src/modules/mavlink/streams/ATTITUDE.hpp new file mode 100644 index 0000000000..e36d4b4e6f --- /dev/null +++ b/src/modules/mavlink/streams/ATTITUDE.hpp @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#ifndef ATTITUDE_HPP +#define ATTITUDE_HPP + +#include +#include + +class MavlinkStreamAttitude : public MavlinkStream +{ +public: + const char *get_name() const override + { + return MavlinkStreamAttitude::get_name_static(); + } + + static constexpr const char *get_name_static() + { + return "ATTITUDE"; + } + + static constexpr uint16_t get_id_static() + { + return MAVLINK_MSG_ID_ATTITUDE; + } + + uint16_t get_id() override + { + return get_id_static(); + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamAttitude(mavlink); + } + + unsigned get_size() override + { + return _att_sub.advertised() ? MAVLINK_MSG_ID_ATTITUDE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0; + } + +private: + uORB::Subscription _att_sub{ORB_ID(vehicle_attitude)}; + uORB::Subscription _angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; + + /* do not allow top copying this class */ + MavlinkStreamAttitude(MavlinkStreamAttitude &) = delete; + MavlinkStreamAttitude &operator = (const MavlinkStreamAttitude &) = delete; + + +protected: + explicit MavlinkStreamAttitude(Mavlink *mavlink) : MavlinkStream(mavlink) + {} + + bool send() override + { + vehicle_attitude_s att; + + if (_att_sub.update(&att)) { + vehicle_angular_velocity_s angular_velocity{}; + _angular_velocity_sub.copy(&angular_velocity); + + mavlink_attitude_t msg{}; + + const matrix::Eulerf euler = matrix::Quatf(att.q); + msg.time_boot_ms = att.timestamp / 1000; + msg.roll = euler.phi(); + msg.pitch = euler.theta(); + msg.yaw = euler.psi(); + + msg.rollspeed = angular_velocity.xyz[0]; + msg.pitchspeed = angular_velocity.xyz[1]; + msg.yawspeed = angular_velocity.xyz[2]; + + mavlink_msg_attitude_send_struct(_mavlink->get_channel(), &msg); + + return true; + } + + return false; + } +}; + +#endif // ATTITUDE_HPP