44 const std::vector<uint8_t> &packet_data = this->
data();
47 if (packet_data.empty())
49 throw std::length_error(
"Packet is empty.");
59 ss <<
"Invalid packet starting byte (0x" 60 << std::uppercase << std::hex
61 <<
static_cast<unsigned int>(packet_data.front())
62 << std::nouppercase <<
"), v1.0 packets should start with 0x" 63 << std::uppercase << std::hex
65 << std::nouppercase <<
".";
66 throw std::invalid_argument(ss.str());
71 throw std::length_error(
72 "Packet (" + std::to_string(packet_data.size()) +
73 " bytes) is shorter than a v1.0 header (" +
79 if (mavlink_get_message_info_by_id(
header(packet_data)->
msgid) ==
88 size_t expected_length =
90 throw std::length_error(
91 "Packet is " + std::to_string(this->
data().size()) +
92 " bytes, should be " +
93 std::to_string(expected_length) +
" bytes.");
120 if (
const mavlink_message_info_t *msg_info =
121 mavlink_get_message_info_by_id(
header(
data())->msgid))
123 return std::string(msg_info->name);
148 if (
const mavlink_msg_entry_t *msg_entry = mavlink_get_msg_entry(
151 int dest_system = -1;
152 int dest_component = 0;
155 if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)
158 size_t offset = msg_entry->target_system_ofs +
160 dest_system =
data()[offset];
164 if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)
167 size_t offset = msg_entry->target_component_ofs +
169 dest_component =
data()[offset];
173 if (dest_system >= 0)
175 return MAVAddress(static_cast<unsigned int>(dest_system),
176 static_cast<unsigned int>(dest_component));
222 size_t expected_length =
224 return data.size() == expected_length;
239 const std::vector<uint8_t> &data)
243 return reinterpret_cast <
Packet(const Packet &other)=default
virtual ::Packet::Version version() const
bool header_complete(const std::vector< uint8_t > &data)
const size_t CHECKSUM_LENGTH
const struct mavlink::v1_header * header(const std::vector< uint8_t > &data)
virtual std::string name() const
const ::Packet::Version VERSION
virtual MAVAddress source() const
virtual std::optional< MAVAddress > dest() const
bool packet_complete(const std::vector< uint8_t > &data)
bool header_complete(const std::vector< uint8_t > &data)
const size_t HEADER_LENGTH
virtual unsigned long id() const
const struct mavlink::v1_header * header(const std::vector< uint8_t > &data)
const std::vector< uint8_t > & data() const