17 #include <mavros_msgs/Mavlink.h> 18 #include <mavconn/mavlink_dialect.h> 23 using ::mavlink::mavlink_message_t;
50 inline bool convert(
const mavros_msgs::Mavlink &rmsg, mavlink_message_t &mmsg)
52 if (rmsg.payload64.size() >
sizeof(mmsg.payload64) /
sizeof(mmsg.payload64[0])) {
56 if (!rmsg.signature.empty() && rmsg.signature.size() !=
sizeof(mmsg.signature)) {
64 mmsg.magic = rmsg.magic;
66 mmsg.incompat_flags = rmsg.incompat_flags;
67 mmsg.compat_flags = rmsg.compat_flags;
69 mmsg.sysid = rmsg.sysid;
70 mmsg.compid = rmsg.compid;
71 mmsg.msgid = rmsg.msgid;
72 mmsg.checksum = rmsg.checksum;
74 std::copy(rmsg.payload64.begin(), rmsg.payload64.end(), mmsg.payload64);
75 std::copy(rmsg.signature.begin(), rmsg.signature.end(), mmsg.signature);
88 inline bool convert(
const mavlink_message_t &mmsg, mavros_msgs::Mavlink &rmsg, uint8_t framing_status = mavros_msgs::Mavlink::FRAMING_OK)
90 const size_t payload64_len = (mmsg.len + 7) / 8;
92 rmsg.framing_status = framing_status;
98 rmsg.magic = mmsg.magic;
100 rmsg.incompat_flags = mmsg.incompat_flags;
101 rmsg.compat_flags = mmsg.compat_flags;
103 rmsg.sysid = mmsg.sysid;
104 rmsg.compid = mmsg.compid;
105 rmsg.msgid = mmsg.msgid;
106 rmsg.checksum = mmsg.checksum;
108 rmsg.payload64 = std::move(mavros_msgs::Mavlink::_payload64_type(mmsg.payload64, mmsg.payload64 + payload64_len));
111 if (mmsg.incompat_flags & MAVLINK_IFLAG_SIGNED)
112 rmsg.signature = std::move(mavros_msgs::Mavlink::_signature_type(mmsg.signature, mmsg.signature +
sizeof(mmsg.signature)));
114 rmsg.signature.clear();
bool convert(const mavros_msgs::Mavlink &rmsg, mavlink_message_t &mmsg)
Convert mavros_msgs/Mavlink message to mavlink_message_t.