mavtables  0.2.1
MAVLink router and firewall.
PacketVersion1.cpp
Go to the documentation of this file.
1 // MAVLink router and firewall.
2 // Copyright (C) 2018 Michael R. Shannon <mrshannon.aerospace@gmail.com>
3 //
4 // This program is free software; you can redistribute it and/or modify
5 // it under the terms of the GNU General Public License as published by
6 // the Free Software Foundation; either version 2 of the License, or
7 // (at your option) any later version.
8 //
9 // This program is distributed in the hope that it will be useful,
10 // but WITHOUT ANY WARRANTY; without even the implied warranty of
11 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 // GNU General Public License for more details.
13 //
14 // You should have received a copy of the GNU General Public License
15 // along with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 
18 #include <cstddef>
19 #include <cstdint>
20 #include <memory>
21 #include <sstream>
22 #include <stdexcept>
23 #include <string>
24 #include <vector>
25 
26 #include "InvalidPacketIDError.hpp"
27 #include "mavlink.hpp"
28 #include "PacketVersion1.hpp"
29 
30 
31 namespace packet_v1
32 {
33 
34  /** \copydoc ::Packet::Packet(std::vector<uint8_t> data)
35  *
36  * \throws std::invalid_argument if packet data does not start with the
37  * magic byte (0xFE).
38  * \throws std::length_error if packet data is either too short or too
39  * long.
40  */
41  Packet::Packet(std::vector<uint8_t> data)
42  : ::Packet(std::move(data))
43  {
44  const std::vector<uint8_t> &packet_data = this->data();
45 
46  // Check that data was given.
47  if (packet_data.empty())
48  {
49  throw std::length_error("Packet is empty.");
50  }
51 
52  // Check that a complete header was given (including magic number).
53  if (!header_complete(packet_data))
54  {
55  // Could be the magic number.
56  if (START_BYTE != packet_data.front())
57  {
58  std::stringstream ss;
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
64  << static_cast<unsigned int>(START_BYTE)
65  << std::nouppercase << ".";
66  throw std::invalid_argument(ss.str());
67  }
68  // Otherwise the packet is not long enough.
69  else
70  {
71  throw std::length_error(
72  "Packet (" + std::to_string(packet_data.size()) +
73  " bytes) is shorter than a v1.0 header (" +
74  std::to_string(HEADER_LENGTH) + " bytes).");
75  }
76  }
77 
78  // Verify the message ID.
79  if (mavlink_get_message_info_by_id(header(packet_data)->msgid) ==
80  nullptr)
81  {
82  throw InvalidPacketIDError(header(packet_data)->msgid);
83  }
84 
85  // Ensure a complete packet was given.
86  if (!packet_complete(packet_data))
87  {
88  size_t expected_length =
89  HEADER_LENGTH + header(packet_data)->len + CHECKSUM_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.");
94  }
95  }
96 
97 
98  /** \copydoc ::Packet::version()
99  *
100  * \returns 0x0100 (v1.0) - ::Packet::V1
101  */
103  {
104  return VERSION;
105  }
106 
107 
108  unsigned long Packet::id() const
109  {
110  return header(data())->msgid;
111  }
112 
113 
114  /** \copydoc ::Packet::name()
115  *
116  * \throws std::runtime_error if the packet data has an invalid ID.
117  */
118  std::string Packet::name() const
119  {
120  if (const mavlink_message_info_t *msg_info =
121  mavlink_get_message_info_by_id(header(data())->msgid))
122  {
123  return std::string(msg_info->name);
124  }
125 
126  // There should never be any way to reach this point since the message
127  // ID was checked in the constructor. It is here just in case the
128  // MAVLink C library has an error in it.
129  // LCOV_EXCL_START
130  throw InvalidPacketIDError(header(data())->msgid);
131  // LCOV_EXCL_STOP
132  }
133 
134 
136  {
137  return MAVAddress(header(data())->sysid, header(data())->compid);
138  }
139 
140 
141  /** \copydoc ::Packet::dest()
142  *
143  * \thanks The [mavlink-router](https://github.com/intel/mavlink-router)
144  * project for an example of how to extract the destination address.
145  */
146  std::optional<MAVAddress> Packet::dest() const
147  {
148  if (const mavlink_msg_entry_t *msg_entry = mavlink_get_msg_entry(
149  header(data())->msgid))
150  {
151  int dest_system = -1;
152  int dest_component = 0;
153 
154  // Extract destination system.
155  if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM)
156  {
157  // target_system_ofs is offset from start of payload
158  size_t offset = msg_entry->target_system_ofs +
159  sizeof(mavlink::v1_header);
160  dest_system = data()[offset];
161  }
162 
163  // Extract destination component.
164  if (msg_entry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT)
165  {
166  // target_compoent_ofs is offset from start of payload
167  size_t offset = msg_entry->target_component_ofs +
168  sizeof(mavlink::v1_header);
169  dest_component = data()[offset];
170  }
171 
172  // Construct MAVLink address.
173  if (dest_system >= 0)
174  {
175  return MAVAddress(static_cast<unsigned int>(dest_system),
176  static_cast<unsigned int>(dest_component));
177  }
178 
179  // No destination address.
180  return {};
181  }
182 
183  // There should never be any way to reach this point since the message
184  // ID was checked in the constructor. It is here just in case the
185  // MAVLink C library has an error in it.
186  // LCOV_EXCL_START
187  throw InvalidPacketIDError(header(data())->msgid);
188  // LCOV_EXCL_STOP
189  }
190 
191 
192  /** Determine if the given data contains a complete v1.0 header.
193  *
194  * \relates packet_v1::Packet
195  * \param data The packet data.
196  * \retval true if \p data contains a complete header (starting with the
197  * magic byte).
198  * \retval false if \p data does not contain a complete v1.0 header.
199  */
200  bool header_complete(const std::vector<uint8_t> &data)
201  {
202  // We cant use the \ref header function here because that would cause
203  // infinite recursion.
204  return (data.size() >= HEADER_LENGTH) &&
205  (START_BYTE == data.front());
206  }
207 
208 
209  /** Determine if the given data contains a complete v1.0 packet.
210  *
211  * \relates packet_v1::Packet
212  * \param data The packet data.
213  * \retval true if \p data contains a complete packet (starting with the
214  * magic byte).
215  * \retval false if \p data does not contain a complete v1.0 packet, or if
216  * there is extra bytes in \p data beyond the packet.
217  */
218  bool packet_complete(const std::vector<uint8_t> &data)
219  {
220  if (header_complete(data))
221  {
222  size_t expected_length =
224  return data.size() == expected_length;
225  }
226 
227  return false;
228  }
229 
230 
231  /** Cast data as a v1.0 packet header structure pointer.
232  *
233  * \relates packet_v1::Packet
234  * \param data The packet data.
235  * \returns A pointer to the given data, cast to a v1.0 header structure.
236  * %If an incomplete header is given a nullptr will be returned.
237  */
238  const struct mavlink::v1_header *header(
239  const std::vector<uint8_t> &data)
240  {
241  if (header_complete(data))
242  {
243  return reinterpret_cast <
244  const struct mavlink::v1_header * >(&(data[0]));
245  }
246 
247  return nullptr;
248  }
249 
250 }
Packet(const Packet &other)=default
STL namespace.
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)
Version
Definition: Packet.hpp:47
virtual std::string name() const
const uint8_t START_BYTE
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
Definition: Packet.cpp:52