mavtables  0.2.1
MAVLink router and firewall.
common_Packet.hpp
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 <cstdint>
19 #include <vector>
20 
21 #include "macros.hpp"
22 #include "mavlink.hpp"
23 
24 
25 namespace
26 {
27 
28  // HEARTBEAT v1.0 structure for testing packets without target
29  // system/component.
30  struct PACKED HeartbeatV1
31  {
32  struct PACKED payload
33  {
34  uint8_t type = 1;
35  uint8_t autopilot = 2;
36  uint8_t base_mode = 3;
37  uint32_t custom_mode = 4;
38  uint8_t system_status = 5;
39  uint8_t mavlink_version = 6;
40  };
41  uint8_t magic = 0xFE;
42  uint8_t len = sizeof(payload);
43  uint8_t seq = 0xFE; // test internal magic byte
44  uint8_t sysid = 127;
45  uint8_t compid = 1;
46  uint8_t msgid = 0;
47  payload payload;
48  uint16_t checksum = 0xFACE;
49  };
50 
51 
52  // PING v1.0 structure for testing target system/compoent.
53  struct PACKED PingV1
54  {
55  struct PACKED payload
56  {
57  uint64_t time_usec = 295128000000000;
58  uint32_t seq = 0xBA5EBA11;
59  uint8_t target_system = 127;
60  uint8_t target_component = 1;
61  };
62  uint8_t magic = 0xFE;
63  uint8_t len = sizeof(payload);
64  uint8_t seq = 0xFE; // test internal magic byte
65  uint8_t sysid = 192;
66  uint8_t compid = 168;
67  uint8_t msgid = 4;
68  payload payload;
69  uint16_t checksum = 0xFACE;
70  };
71 
72 
73  // SET_MODE v1.0 structure for testing target system only.
74  struct PACKED SetModeV1
75  {
76  struct PACKED payload
77  {
78  uint32_t custom_mode = 2;
79  uint8_t target_system = 123;
80  uint8_t base_mode = 0xFE; // test magic byte in payload
81  };
82  uint8_t magic = 0xFE;
83  uint8_t len = sizeof(payload);
84  uint8_t seq = 0xFE; // test internal magic byte
85  uint8_t sysid = 172;
86  uint8_t compid = 0;
87  uint8_t msgid = 11;
88  payload payload;
89  uint16_t checksum = 0xFACE;
90  };
91 
92 
93  // ENCAPSULATED_DATA v1.0 structure for testing maximum length packets.
94  struct PACKED EncapsulatedDataV1
95  {
96  struct PACKED payload
97  {
98  uint16_t seqnr = 0;
99  uint8_t data[253] = {
100  0, 1, 2, 3, 4, 5, 6, 7, 8, 9,
101  10, 11, 12, 13, 14, 15, 16, 17, 18, 19,
102  20, 21, 22, 23, 24, 25, 26, 27, 28, 29,
103  30, 31, 32, 33, 34, 35, 36, 37, 38, 39,
104  40, 41, 42, 43, 44, 45, 46, 47, 48, 49,
105  50, 51, 52, 53, 54, 55, 56, 57, 58, 59,
106  60, 61, 62, 63, 64, 65, 66, 67, 68, 69,
107  70, 71, 72, 73, 74, 75, 76, 77, 78, 79,
108  80, 81, 82, 83, 84, 85, 86, 87, 88, 89,
109  90, 91, 92, 93, 94, 95, 96, 97, 98, 99,
110  100, 101, 102, 103, 104, 105, 106, 107, 108, 109,
111  110, 111, 112, 113, 114, 115, 116, 117, 118, 119,
112  120, 121, 122, 123, 124, 125, 126, 127, 128, 129,
113  130, 131, 132, 133, 134, 135, 136, 137, 138, 139,
114  140, 141, 142, 143, 144, 145, 146, 147, 148, 149,
115  150, 151, 152, 153, 154, 155, 156, 157, 158, 159,
116  160, 161, 162, 163, 164, 165, 166, 167, 168, 169,
117  170, 171, 172, 173, 174, 175, 176, 177, 178, 179,
118  180, 181, 182, 183, 184, 185, 186, 187, 188, 189,
119  190, 191, 192, 193, 194, 195, 196, 197, 198, 199,
120  200, 201, 202, 203, 204, 205, 206, 207, 208, 209,
121  210, 211, 212, 213, 214, 215, 216, 217, 218, 219,
122  220, 221, 222, 223, 224, 225, 226, 227, 228, 229,
123  230, 231, 232, 233, 234, 235, 236, 237, 238, 239,
124  240, 241, 242, 243, 244, 245, 246, 247, 248, 249,
125  250, 251, 252
126  };
127  };
128  uint8_t magic = 0xFE;
129  uint8_t len = 255;
130  uint8_t seq = 0xFE; // test internal magic byte
131  uint8_t sysid = 224;
132  uint8_t compid = 255;
133  uint8_t msgid = 131;
134  payload payload;
135  uint16_t checksum = 0xFACE;
136  };
137 
138 
139 #ifdef __clang__
140  #pragma clang diagnostic push
141  #pragma clang diagnostic ignored "-Wunused-member-function"
142 #endif
143 
144  // HEARTBEAT v2.0 structure for testing packets without target
145  // system/component.
146  struct PACKED HeartbeatV2
147  {
148  struct PACKED payload
149  {
150  uint8_t type = 1;
151  uint8_t autopilot = 2;
152  uint8_t base_mode = 3;
153  uint32_t custom_mode = 4;
154  uint8_t system_status = 5;
155  uint8_t mavlink_version = 6;
156  };
157  uint8_t magic = 0xFD;
158  uint8_t len = sizeof(payload);
159  uint8_t incompat_flags = 0;
160  uint8_t compat_flags = 0;
161  uint8_t seq = 0xFD; // test internal magic byte
162  uint8_t sysid = 127;
163  uint8_t compid = 1;
164  uint32_t msgid : 24;
165  payload payload;
166  uint16_t checksum = 0xFACE;
167  HeartbeatV2() : msgid(0) {}
168  };
169 
170 
171  // PING v2.0 structure for testing target system/component.
172  struct PACKED PingV2
173  {
174  struct PACKED payload
175  {
176  uint64_t time_usec = 295128000000000;
177  uint32_t seq = 0xBA5EBA11;
178  uint8_t target_system = 127;
179  uint8_t target_component = 1;
180  };
181  uint8_t magic = 0xFD;
182  uint8_t len = sizeof(payload);
183  uint8_t incompat_flags = 0;
184  uint8_t compat_flags = 0;
185  uint8_t seq = 0xFD; // test internal magic byte
186  uint8_t sysid = 192;
187  uint8_t compid = 168;
188  uint32_t msgid : 24;
189  payload payload;
190  uint16_t checksum = 0xFACE;
191  PingV2() : msgid(4) {}
192  };
193 
194 
195  // SET_MODE v2.0 structure for testing target system only.
196  struct PACKED SetModeV2
197  {
198  struct PACKED payload
199  {
200  uint32_t custom_mode = 2;
201  uint8_t target_system = 123;
202  uint8_t base_mode = 0xFD; // test magic byte in payload
203  };
204  uint8_t magic = 0xFD;
205  uint8_t len = sizeof(payload);
206  uint8_t incompat_flags = 0;
207  uint8_t compat_flags = 0;
208  uint8_t seq = 0xFD; // test internal magic byte
209  uint8_t sysid = 172;
210  uint8_t compid = 0;
211  uint32_t msgid : 24;
212  payload payload;
213  uint16_t checksum = 0xFACE;
214  SetModeV2() : msgid(11) {}
215  };
216 
217 
218  // MISSION_SET_CURRENT v2.0 for testing trimmed out target system and
219  // components.
220  struct PACKED MissionSetCurrentV2
221  {
222  struct PACKED payload
223  {
224  uint16_t seq = 0xFD; // test magic byte in payload
225  // uint8_t target_system = 0;
226  // uint8_t target_component = 0;
227  };
228  uint8_t magic = 0xFD;
229  uint8_t len = sizeof(payload);
230  uint8_t incompat_flags = 0;
231  uint8_t compat_flags = 0;
232  uint8_t seq = 0xFD; // test internal magic byte
233  uint8_t sysid = 255;
234  uint8_t compid = 0;
235  uint32_t msgid : 24;
236  payload payload;
237  uint16_t checksum = 0xFACE;
238  MissionSetCurrentV2() : msgid(41) {}
239  };
240 
241 
242  // ENCAPSULATED_DATA v2.0 structure for testing maximum length packets.
243  struct PACKED EncapsulatedDataV2
244  {
245  struct PACKED payload
246  {
247  uint16_t seqnr = 0;
248  uint8_t data[253] = {
249  0, 1, 2, 3, 4, 5, 6, 7, 8, 9,
250  10, 11, 12, 13, 14, 15, 16, 17, 18, 19,
251  20, 21, 22, 23, 24, 25, 26, 27, 28, 29,
252  30, 31, 32, 33, 34, 35, 36, 37, 38, 39,
253  40, 41, 42, 43, 44, 45, 46, 47, 48, 49,
254  50, 51, 52, 53, 54, 55, 56, 57, 58, 59,
255  60, 61, 62, 63, 64, 65, 66, 67, 68, 69,
256  70, 71, 72, 73, 74, 75, 76, 77, 78, 79,
257  80, 81, 82, 83, 84, 85, 86, 87, 88, 89,
258  90, 91, 92, 93, 94, 95, 96, 97, 98, 99,
259  100, 101, 102, 103, 104, 105, 106, 107, 108, 109,
260  110, 111, 112, 113, 114, 115, 116, 117, 118, 119,
261  120, 121, 122, 123, 124, 125, 126, 127, 128, 129,
262  130, 131, 132, 133, 134, 135, 136, 137, 138, 139,
263  140, 141, 142, 143, 144, 145, 146, 147, 148, 149,
264  150, 151, 152, 153, 154, 155, 156, 157, 158, 159,
265  160, 161, 162, 163, 164, 165, 166, 167, 168, 169,
266  170, 171, 172, 173, 174, 175, 176, 177, 178, 179,
267  180, 181, 182, 183, 184, 185, 186, 187, 188, 189,
268  190, 191, 192, 193, 194, 195, 196, 197, 198, 199,
269  200, 201, 202, 203, 204, 205, 206, 207, 208, 209,
270  210, 211, 212, 213, 214, 215, 216, 217, 218, 219,
271  220, 221, 222, 223, 224, 225, 226, 227, 228, 229,
272  230, 231, 232, 233, 234, 235, 236, 237, 238, 239,
273  240, 241, 242, 243, 244, 245, 246, 247, 248, 249,
274  250, 251, 252
275  };
276  };
277  uint8_t magic = 0xFD;
278  uint8_t len = sizeof(payload);
279  uint8_t incompat_flags = 0;
280  uint8_t compat_flags = 0;
281  uint8_t seq = 0xFD; // test internal magic byte
282  uint8_t sysid = 224;
283  uint8_t compid = 255;
284  uint32_t msgid : 24;
285  payload payload;
286  uint16_t checksum = 0xFACE;
287  EncapsulatedDataV2() : msgid(131) {}
288  };
289 
290 
291  // PARAM_EXT_REQUEST_LIST v2.0 structure for testing message ID's beyond
292  // 255.
293  struct PACKED ParamExtRequestListV2
294  {
295  struct PACKED payload
296  {
297  uint8_t target_system = 32;
298  uint8_t target_component = 64;
299  };
300  uint8_t magic = 0xFD;
301  uint8_t len = sizeof(payload);
302  uint8_t incompat_flags = 0;
303  uint8_t compat_flags = 0;
304  uint8_t seq = 0xFD; // test internal magic byte
305  uint8_t sysid = 0;
306  uint8_t compid = 255;
307  uint32_t msgid : 24;
308  payload payload;
309  uint16_t checksum = 0xFACE;
310  ParamExtRequestListV2() : msgid(321) {}
311  };
312 
313 #ifdef __clang__
314  #pragma clang diagnostic pop
315 #endif
316 
317 
318 #ifdef __clang__
319  #pragma clang diagnostic push
320  #pragma clang diagnostic ignored "-Wunused-template"
321 #endif
322 
323  // Convert a MAVLink packet structure to a vector of bytes.
324  template <class T>
325  static std::vector<uint8_t> to_vector(T packet)
326  {
327  std::vector<uint8_t> data;
328  data.assign(reinterpret_cast<uint8_t *>(&packet),
329  reinterpret_cast<uint8_t *>(&packet) + sizeof(packet));
330  return data;
331  }
332 
333 
334  // Convert a MAVLink packet structure to a vector of bytes with signature.
335  template <class T>
336  static std::vector<uint8_t> to_vector_with_sig(T packet)
337  {
338  std::vector<uint8_t> data;
339  packet.incompat_flags |= MAVLINK_IFLAG_SIGNED;
340 
341  data.assign(reinterpret_cast<uint8_t *>(&packet),
342  reinterpret_cast<uint8_t *>(&packet) + sizeof(packet));
343  std::vector<uint8_t> sig =
344  {
345  1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13
346  };
347  data.insert(std::end(data), std::begin(sig), std::end(sig));
348  return data;
349  }
350 
351 #ifdef __clang__
352  #pragma clang diagnostic pop
353 #endif
354 
355 }
#define PACKED
Definition: macros.hpp:41