Browse Source

mavlink: move HOME_POSITION to separate stream header

release/1.12
Daniel Agar 4 years ago
parent
commit
3964cfb3a7
  1. 88
      src/modules/mavlink/mavlink_messages.cpp
  2. 97
      src/modules/mavlink/streams/HOME_POSITION.hpp

88
src/modules/mavlink/mavlink_messages.cpp

@ -117,6 +117,7 @@ using matrix::wrap_2pi; @@ -117,6 +117,7 @@ using matrix::wrap_2pi;
#include "streams/FLIGHT_INFORMATION.hpp"
#include "streams/GPS_GLOBAL_ORIGIN.hpp"
#include "streams/GPS_STATUS.hpp"
#include "streams/HOME_POSITION.hpp"
#include "streams/HIGH_LATENCY2.hpp"
#include "streams/HIL_ACTUATOR_CONTROLS.hpp"
#include "streams/HIL_STATE_QUATERNION.hpp"
@ -3054,91 +3055,6 @@ protected: @@ -3054,91 +3055,6 @@ protected:
}
};
class MavlinkStreamHomePosition : public MavlinkStream
{
public:
const char *get_name() const override
{
return MavlinkStreamHomePosition::get_name_static();
}
static constexpr const char *get_name_static()
{
return "HOME_POSITION";
}
static constexpr uint16_t get_id_static()
{
return MAVLINK_MSG_ID_HOME_POSITION;
}
uint16_t get_id() override
{
return get_id_static();
}
static MavlinkStream *new_instance(Mavlink *mavlink)
{
return new MavlinkStreamHomePosition(mavlink);
}
unsigned get_size() override
{
return _home_sub.advertised() ? (MAVLINK_MSG_ID_HOME_POSITION_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
}
private:
uORB::Subscription _home_sub{ORB_ID(home_position)};
/* do not allow top copying this class */
MavlinkStreamHomePosition(MavlinkStreamHomePosition &) = delete;
MavlinkStreamHomePosition &operator = (const MavlinkStreamHomePosition &) = delete;
protected:
explicit MavlinkStreamHomePosition(Mavlink *mavlink) : MavlinkStream(mavlink)
{}
bool send() override
{
/* we're sending the GPS home periodically to ensure the
* the GCS does pick it up at one point */
home_position_s home;
if (_home_sub.advertised() && _home_sub.copy(&home)) {
if (home.valid_hpos) {
mavlink_home_position_t msg{};
msg.latitude = home.lat * 1e7;
msg.longitude = home.lon * 1e7;
msg.altitude = home.alt * 1e3f;
msg.x = home.x;
msg.y = home.y;
msg.z = home.z;
matrix::Quatf q(matrix::Eulerf(0.0f, 0.0f, home.yaw));
msg.q[0] = q(0);
msg.q[1] = q(1);
msg.q[2] = q(2);
msg.q[3] = q(3);
msg.approach_x = 0.0f;
msg.approach_y = 0.0f;
msg.approach_z = 0.0f;
msg.time_usec = home.timestamp;
mavlink_msg_home_position_send_struct(_mavlink->get_channel(), &msg);
return true;
}
}
return false;
}
};
class MavlinkStreamCameraCapture : public MavlinkStream
{
public:
@ -3258,7 +3174,9 @@ static const StreamListItem streams_list[] = { @@ -3258,7 +3174,9 @@ static const StreamListItem streams_list[] = {
create_stream_list_item<MavlinkStreamAutopilotStateForGimbalDevice>(),
create_stream_list_item<MavlinkStreamGimbalDeviceSetAttitude>(),
#endif
#if defined(HOME_POSITION_HPP)
create_stream_list_item<MavlinkStreamHomePosition>(),
#endif // HOME_POSITION_HPP
#if defined(SERVO_OUTPUT_RAW_HPP)
create_stream_list_item<MavlinkStreamServoOutputRaw<0> >(),
create_stream_list_item<MavlinkStreamServoOutputRaw<1> >(),

97
src/modules/mavlink/streams/HOME_POSITION.hpp

@ -0,0 +1,97 @@ @@ -0,0 +1,97 @@
/****************************************************************************
*
* 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 HOME_POSITION_HPP
#define HOME_POSITION_HPP
#include <uORB/topics/home_position.h>
class MavlinkStreamHomePosition : public MavlinkStream
{
public:
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamHomePosition(mavlink); }
static constexpr const char *get_name_static() { return "HOME_POSITION"; }
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_HOME_POSITION; }
const char *get_name() const override { return get_name_static(); }
uint16_t get_id() override { return get_id_static(); }
unsigned get_size() override
{
return _home_sub.advertised() ? (MAVLINK_MSG_ID_HOME_POSITION_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
}
private:
explicit MavlinkStreamHomePosition(Mavlink *mavlink) : MavlinkStream(mavlink) {}
uORB::Subscription _home_sub{ORB_ID(home_position)};
bool send() override
{
// we're sending the GPS home periodically to ensure the
// the GCS does pick it up at one point
home_position_s home;
if (_home_sub.advertised() && _home_sub.copy(&home)) {
if (home.valid_hpos) {
mavlink_home_position_t msg{};
msg.latitude = home.lat * 1e7;
msg.longitude = home.lon * 1e7;
msg.altitude = home.alt * 1e3f;
msg.x = home.x;
msg.y = home.y;
msg.z = home.z;
matrix::Quatf q(matrix::Eulerf(0.f, 0.f, home.yaw));
q.copyTo(msg.q);
msg.approach_x = 0.f;
msg.approach_y = 0.f;
msg.approach_z = 0.f;
msg.time_usec = home.timestamp;
mavlink_msg_home_position_send_struct(_mavlink->get_channel(), &msg);
return true;
}
}
return false;
}
};
#endif // HOME_POSITION_HPP
Loading…
Cancel
Save