mavtables  0.2.1
MAVLink router and firewall.
test_PacketVersion2.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 <memory>
19 #include <optional>
20 #include <stdexcept>
21 #include <utility>
22 
23 #include <catch.hpp>
24 #include <fakeit.hpp>
25 
26 #include "config.hpp"
27 #include "Connection.hpp"
28 #include "InvalidPacketIDError.hpp"
29 #include "MAVAddress.hpp"
30 #include "mavlink.hpp"
31 #include "PacketVersion2.hpp"
32 #include "utility.hpp"
33 
34 #include "common.hpp"
35 #include "common_Packet.hpp"
36 
37 
38 TEST_CASE("'packet_v2::header_complete' determines whether the given bytes "
39  "at least represent a complete header.", "[packet_v2]")
40 {
41  auto heartbeat = to_vector_with_sig(HeartbeatV2());
42  auto ping = to_vector(PingV2());
43  auto set_mode = to_vector_with_sig(SetModeV2());
44  auto mission_set_current = to_vector(MissionSetCurrentV2());
45  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
46  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
47  SECTION("Returns true when at least a complete header is given.")
48  {
49  heartbeat.resize(10);
50  ping.resize(15);
51  set_mode.resize(20);
52  mission_set_current.resize(25);
53  encapsulated_data.resize(30);
56  REQUIRE(packet_v2::header_complete(set_mode));
57  REQUIRE(packet_v2::header_complete(mission_set_current));
58  REQUIRE(packet_v2::header_complete(encapsulated_data));
59  REQUIRE(packet_v2::header_complete(param_ext_request_list));
60  }
61  SECTION("Returns false when an incomplete header is given.")
62  {
63  heartbeat.resize(5);
64  ping.resize(4);
65  set_mode.resize(3);
66  mission_set_current.resize(2);
67  encapsulated_data.resize(1);
68  param_ext_request_list.resize(0);
69  REQUIRE_FALSE(packet_v2::header_complete(heartbeat));
70  REQUIRE_FALSE(packet_v2::header_complete(ping));
71  REQUIRE_FALSE(packet_v2::header_complete(set_mode));
72  REQUIRE_FALSE(packet_v2::header_complete(mission_set_current));
73  REQUIRE_FALSE(packet_v2::header_complete(encapsulated_data));
74  REQUIRE_FALSE(packet_v2::header_complete(param_ext_request_list));
75  }
76  SECTION("Returns false when the magic byte is wrong.")
77  {
78  heartbeat.front() = 0xAD;
79  ping.front() = 0xBC;
80  set_mode.front() = 0xFE;
81  mission_set_current.front() = 0xFE;
82  encapsulated_data.front() = 0xFE;
83  param_ext_request_list.front() = 0xFE;
84  REQUIRE_FALSE(packet_v2::header_complete(heartbeat));
85  REQUIRE_FALSE(packet_v2::header_complete(ping));
86  REQUIRE_FALSE(packet_v2::header_complete(set_mode));
87  REQUIRE_FALSE(packet_v2::header_complete(mission_set_current));
88  REQUIRE_FALSE(packet_v2::header_complete(encapsulated_data));
89  REQUIRE_FALSE(packet_v2::header_complete(param_ext_request_list));
90  }
91 }
92 
93 
94 TEST_CASE("'packet_v2::header' returns a structure pointer to the given "
95  "header data.", "[packet_v2]")
96 {
97  auto heartbeat = to_vector_with_sig(HeartbeatV2());
98  auto ping = to_vector(PingV2());
99  auto set_mode = to_vector_with_sig(SetModeV2());
100  auto mission_set_current = to_vector(MissionSetCurrentV2());
101  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
102  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
103  SECTION("Header contains a magic value.")
104  {
105  REQUIRE(packet_v2::header(heartbeat)->magic == 0xFD);
106  REQUIRE(packet_v2::header(ping)->magic == 0xFD);
107  REQUIRE(packet_v2::header(set_mode)->magic == 0xFD);
108  REQUIRE(packet_v2::header(mission_set_current)->magic == 0xFD);
109  REQUIRE(packet_v2::header(encapsulated_data)->magic == 0xFD);
110  REQUIRE(packet_v2::header(param_ext_request_list)->magic == 0xFD);
111  }
112  SECTION("Header stores the packet length.")
113  {
114  REQUIRE(packet_v2::header(heartbeat)->len == 9);
115  REQUIRE(packet_v2::header(ping)->len == 14);
116  REQUIRE(packet_v2::header(set_mode)->len == 6);
117  REQUIRE(packet_v2::header(mission_set_current)->len == 2);
118  REQUIRE(packet_v2::header(encapsulated_data)->len == 255);
119  REQUIRE(packet_v2::header(param_ext_request_list)->len == 2);
120  }
121  SECTION("Header has incompatibility flags.")
122  {
123  REQUIRE((packet_v2::header(heartbeat)->incompat_flags &
124  MAVLINK_IFLAG_SIGNED) == true);
125  REQUIRE((packet_v2::header(ping)->incompat_flags &
126  MAVLINK_IFLAG_SIGNED) == false);
127  REQUIRE((packet_v2::header(set_mode)->incompat_flags &
128  MAVLINK_IFLAG_SIGNED) == true);
129  REQUIRE((packet_v2::header(mission_set_current)->incompat_flags &
130  MAVLINK_IFLAG_SIGNED) == false);
131  REQUIRE((packet_v2::header(encapsulated_data)->incompat_flags &
132  MAVLINK_IFLAG_SIGNED) == true);
133  REQUIRE((packet_v2::header(param_ext_request_list)->incompat_flags &
134  MAVLINK_IFLAG_SIGNED) == false);
135  }
136  SECTION("Header has compatibility flags.")
137  {
138  REQUIRE(packet_v2::header(heartbeat)->compat_flags == 0);
139  REQUIRE(packet_v2::header(ping)->compat_flags == 0);
140  REQUIRE(packet_v2::header(set_mode)->compat_flags == 0);
141  REQUIRE(packet_v2::header(mission_set_current)->compat_flags == 0);
142  REQUIRE(packet_v2::header(encapsulated_data)->compat_flags == 0);
143  REQUIRE(packet_v2::header(param_ext_request_list)->compat_flags == 0);
144  }
145  SECTION("Header has a sequence number.")
146  {
147  REQUIRE(packet_v2::header(heartbeat)->seq == 0xFD);
148  REQUIRE(packet_v2::header(ping)->seq == 0xFD);
149  REQUIRE(packet_v2::header(set_mode)->seq == 0xFD);
150  REQUIRE(packet_v2::header(mission_set_current)->seq == 0xFD);
151  REQUIRE(packet_v2::header(encapsulated_data)->seq == 0xFD);
152  REQUIRE(packet_v2::header(param_ext_request_list)->seq == 0xFD);
153  }
154  SECTION("Header has a system ID.")
155  {
156  REQUIRE(packet_v2::header(heartbeat)->sysid == 127);
157  REQUIRE(packet_v2::header(ping)->sysid == 192);
158  REQUIRE(packet_v2::header(set_mode)->sysid == 172);
159  REQUIRE(packet_v2::header(mission_set_current)->sysid == 255);
160  REQUIRE(packet_v2::header(encapsulated_data)->sysid == 224);
161  REQUIRE(packet_v2::header(param_ext_request_list)->sysid == 0);
162  }
163  SECTION("Header has a component ID.")
164  {
165  REQUIRE(packet_v2::header(heartbeat)->compid == 1);
166  REQUIRE(packet_v2::header(ping)->compid == 168);
167  REQUIRE(packet_v2::header(set_mode)->compid == 0);
168  REQUIRE(packet_v2::header(mission_set_current)->compid == 0);
169  REQUIRE(packet_v2::header(encapsulated_data)->compid == 255);
170  REQUIRE(packet_v2::header(param_ext_request_list)->compid == 255);
171  }
172  SECTION("Header has a message ID.")
173  {
174  REQUIRE(packet_v2::header(heartbeat)->msgid == 0);
175  REQUIRE(packet_v2::header(ping)->msgid == 4);
176  REQUIRE(packet_v2::header(set_mode)->msgid == 11);
177  REQUIRE(packet_v2::header(mission_set_current)->msgid == 41);
178  REQUIRE(packet_v2::header(encapsulated_data)->msgid == 131);
179  REQUIRE(packet_v2::header(param_ext_request_list)->msgid == 321);
180  }
181  SECTION("Returns nullptr when an incomplete header is given.")
182  {
183  heartbeat.resize(5);
184  ping.resize(4);
185  set_mode.resize(3);
186  mission_set_current.resize(2);
187  encapsulated_data.resize(1);
188  param_ext_request_list.resize(0);
189  REQUIRE(packet_v2::header(heartbeat) == nullptr);
190  REQUIRE(packet_v2::header(ping) == nullptr);
191  REQUIRE(packet_v2::header(set_mode) == nullptr);
192  REQUIRE(packet_v2::header(mission_set_current) == nullptr);
193  REQUIRE(packet_v2::header(encapsulated_data) == nullptr);
194  REQUIRE(packet_v2::header(param_ext_request_list) == nullptr);
195  }
196  SECTION("Returns nullptr when the magic byte is wrong.")
197  {
198  heartbeat.front() = 0xAD;
199  ping.front() = 0xBC;
200  set_mode.front() = 0xFE;
201  mission_set_current.front() = 0xFE;
202  encapsulated_data.front() = 0xFE;
203  param_ext_request_list.front() = 0xFE;
204  REQUIRE(packet_v2::header(heartbeat) == nullptr);
205  REQUIRE(packet_v2::header(ping) == nullptr);
206  REQUIRE(packet_v2::header(set_mode) == nullptr);
207  REQUIRE(packet_v2::header(mission_set_current) == nullptr);
208  REQUIRE(packet_v2::header(encapsulated_data) == nullptr);
209  REQUIRE(packet_v2::header(param_ext_request_list) == nullptr);
210  }
211 }
212 
213 
214 TEST_CASE("'packet_v2::packet_complete' determines whether the given bytes "
215  "represent a complete packet.", "[packet_v2]")
216 {
217  auto heartbeat = to_vector_with_sig(HeartbeatV2());
218  auto ping = to_vector(PingV2());
219  auto set_mode = to_vector_with_sig(SetModeV2());
220  auto mission_set_current = to_vector(MissionSetCurrentV2());
221  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
222  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
223  SECTION("Returns true when a complete packet is given.")
224  {
227  REQUIRE(packet_v2::packet_complete(set_mode));
228  REQUIRE(packet_v2::packet_complete(mission_set_current));
229  REQUIRE(packet_v2::packet_complete(encapsulated_data));
230  REQUIRE(packet_v2::packet_complete(param_ext_request_list));
231  }
232  SECTION("Returns false when the magic byte is wrong.")
233  {
234  heartbeat.front() = 0xAD;
235  ping.front() = 0xBC;
236  set_mode.front() = 0xFE;
237  mission_set_current.front() = 0xFE;
238  encapsulated_data.front() = 0xFE;
239  param_ext_request_list.front() = 0xFE;
240  REQUIRE_FALSE(packet_v2::packet_complete(heartbeat));
241  REQUIRE_FALSE(packet_v2::packet_complete(ping));
242  REQUIRE_FALSE(packet_v2::packet_complete(set_mode));
243  REQUIRE_FALSE(packet_v2::packet_complete(mission_set_current));
244  REQUIRE_FALSE(packet_v2::packet_complete(encapsulated_data));
245  REQUIRE_FALSE(packet_v2::packet_complete(param_ext_request_list));
246  }
247  SECTION("Returns false when the packet is too short.")
248  {
249  heartbeat.pop_back();
250  ping.pop_back();
251  set_mode.pop_back();
252  mission_set_current.pop_back();
253  encapsulated_data.pop_back();
254  param_ext_request_list.pop_back();
255  REQUIRE_FALSE(packet_v2::packet_complete(heartbeat));
256  REQUIRE_FALSE(packet_v2::packet_complete(ping));
257  REQUIRE_FALSE(packet_v2::packet_complete(set_mode));
258  REQUIRE_FALSE(packet_v2::packet_complete(mission_set_current));
259  REQUIRE_FALSE(packet_v2::packet_complete(encapsulated_data));
260  REQUIRE_FALSE(packet_v2::packet_complete(param_ext_request_list));
261  }
262  SECTION("Returns false when the packet is too long.")
263  {
264  heartbeat.push_back(0x00);
265  ping.push_back(0x00);
266  set_mode.push_back(0x00);
267  mission_set_current.push_back(0x00);
268  encapsulated_data.push_back(0x00);
269  param_ext_request_list.push_back(0x00);
270  REQUIRE_FALSE(packet_v2::packet_complete(heartbeat));
271  REQUIRE_FALSE(packet_v2::packet_complete(ping));
272  REQUIRE_FALSE(packet_v2::packet_complete(set_mode));
273  REQUIRE_FALSE(packet_v2::packet_complete(encapsulated_data));
274  REQUIRE_FALSE(packet_v2::packet_complete(encapsulated_data));
275  REQUIRE_FALSE(packet_v2::packet_complete(param_ext_request_list));
276  }
277 }
278 
279 
280 TEST_CASE("'packet_v2::is_signed' determines whether the given bytes "
281  "represent a signed packet.", "[packet_v2]")
282 {
283  auto heartbeat = to_vector_with_sig(HeartbeatV2());
284  auto ping = to_vector(PingV2());
285  auto set_mode = to_vector_with_sig(SetModeV2());
286  auto mission_set_current = to_vector(MissionSetCurrentV2());
287  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
288  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
289  SECTION("Returns true when the packet is signed.")
290  {
292  REQUIRE(packet_v2::is_signed(set_mode));
293  REQUIRE(packet_v2::is_signed(encapsulated_data));
294  }
295  SECTION("Returns false when the packet is not signed.")
296  {
297  REQUIRE_FALSE(packet_v2::is_signed(ping));
298  REQUIRE_FALSE(packet_v2::is_signed(mission_set_current));
299  REQUIRE_FALSE(packet_v2::is_signed(param_ext_request_list));
300  }
301  SECTION("Throws and error when the header is invalid.")
302  {
303  heartbeat.front() = 0xAD;
304  ping.front() = 0xBC;
305  set_mode.front() = 0xFE;
306  mission_set_current.resize(2);
307  encapsulated_data.resize(1);
308  param_ext_request_list.resize(0);
309  // Errors
310  REQUIRE_THROWS_AS(
311  packet_v2::is_signed(heartbeat), std::invalid_argument);
312  REQUIRE_THROWS_AS(
313  packet_v2::is_signed(ping), std::invalid_argument);
314  REQUIRE_THROWS_AS(
315  packet_v2::is_signed(set_mode), std::invalid_argument);
316  REQUIRE_THROWS_AS(
317  packet_v2::is_signed(mission_set_current), std::invalid_argument);
318  REQUIRE_THROWS_AS(
319  packet_v2::is_signed(encapsulated_data), std::invalid_argument);
320  REQUIRE_THROWS_AS(
321  packet_v2::is_signed(param_ext_request_list),
322  std::invalid_argument);
323  // Error messages.
324  REQUIRE_THROWS_WITH(
326  "Header is incomplete or invalid.");
327  REQUIRE_THROWS_WITH(
329  "Header is incomplete or invalid.");
330  REQUIRE_THROWS_WITH(
331  packet_v2::is_signed(set_mode),
332  "Header is incomplete or invalid.");
333  REQUIRE_THROWS_WITH(
334  packet_v2::is_signed(mission_set_current),
335  "Header is incomplete or invalid.");
336  REQUIRE_THROWS_WITH(
337  packet_v2::is_signed(encapsulated_data),
338  "Header is incomplete or invalid.");
339  REQUIRE_THROWS_WITH(
340  packet_v2::is_signed(param_ext_request_list),
341  "Header is incomplete or invalid.");
342  }
343 }
344 
345 
346 TEST_CASE("packet_v2::Packet's can be constructed.", "[packet_v2::Packet]")
347 {
348  HeartbeatV2 heartbeat;
349  PingV2 ping;
350  SetModeV2 set_mode;
351  MissionSetCurrentV2 mission_set_current;
352  EncapsulatedDataV2 encapsulated_data;
353  ParamExtRequestListV2 param_ext_request_list;
354  SECTION("With proper arguments and no signature.")
355  {
356  REQUIRE_NOTHROW(packet_v2::Packet(to_vector(heartbeat)));
357  REQUIRE_NOTHROW(packet_v2::Packet(to_vector(ping)));
358  REQUIRE_NOTHROW(packet_v2::Packet(to_vector(set_mode)));
359  REQUIRE_NOTHROW(packet_v2::Packet(to_vector(mission_set_current)));
360  REQUIRE_NOTHROW(packet_v2::Packet(to_vector(encapsulated_data)));
361  REQUIRE_NOTHROW(packet_v2::Packet(to_vector(param_ext_request_list)));
362  }
363  SECTION("With proper arguments and a signature.")
364  {
365  REQUIRE_NOTHROW(packet_v2::Packet(to_vector_with_sig(heartbeat)));
366  REQUIRE_NOTHROW(packet_v2::Packet(to_vector_with_sig(ping)));
367  REQUIRE_NOTHROW(packet_v2::Packet(to_vector_with_sig(set_mode)));
368  REQUIRE_NOTHROW(
369  packet_v2::Packet(to_vector_with_sig(mission_set_current)));
370  REQUIRE_NOTHROW(
371  packet_v2::Packet(to_vector_with_sig(encapsulated_data)));
372  REQUIRE_NOTHROW(
373  packet_v2::Packet(to_vector_with_sig(param_ext_request_list)));
374  }
375  SECTION("And ensures a complete header is given.")
376  {
377  // 0 length packet.
378  REQUIRE_THROWS_AS(packet_v2::Packet({}), std::length_error);
379  REQUIRE_THROWS_WITH(packet_v2::Packet({}), "Packet is empty.");
380  // Packet short 1 byte.
381  REQUIRE_THROWS_AS(
382  packet_v2::Packet({0xFD, 2, 3, 4, 5, 6, 7, 8, 9}),
383  std::length_error);
384  REQUIRE_THROWS_WITH(
385  packet_v2::Packet({0xFD, 2, 3, 4, 5, 6, 7, 8, 9}),
386  "Packet (9 bytes) is shorter than a v2.0 header (10 bytes).");
387  }
388  SECTION("And ensures packets begin with the magic byte (0xFD).")
389  {
390  ping.magic = 0xAD;
391  REQUIRE_THROWS_AS(
392  packet_v2::Packet(to_vector(ping)), std::invalid_argument);
393  REQUIRE_THROWS_WITH(
394  packet_v2::Packet(to_vector(ping)),
395  "Invalid packet starting byte (0xAD), "
396  "v2.0 packets should start with 0xFD.");
397  }
398  SECTION("And ensures the message ID is valid.")
399  {
400  ping.msgid = 255; // ID 255 is not currently valid.
401  REQUIRE_THROWS_AS(
403  REQUIRE_THROWS_WITH(
404  packet_v2::Packet(to_vector(ping)),
405  "Packet ID (#255) is not part of the '"
406  MAVLINK_DIALECT "' MAVLink dialect.");
407  ping.msgid = 5000; // ID 5000 is not currently valid.
408  REQUIRE_THROWS_AS(
410  REQUIRE_THROWS_WITH(
411  packet_v2::Packet(to_vector(ping)),
412  "Packet ID (#5000) is not part of the '"
413  MAVLINK_DIALECT "' MAVLink dialect.");
414  }
415  SECTION("And ensures the packet is the correct length (without signature).")
416  {
417  // HEARTBEAT (no target system/component).
418  auto heartbeat_data = to_vector(heartbeat);
419  heartbeat_data.push_back(0x00);
420  REQUIRE_THROWS_AS(packet_v2::Packet(heartbeat_data), std::length_error);
421  REQUIRE_THROWS_WITH(
422  packet_v2::Packet(heartbeat_data),
423  "Packet is 22 bytes, should be 21 bytes.");
424  // PING (with target system/component).
425  auto ping_data = to_vector(ping);
426  ping_data.pop_back();
427  REQUIRE_THROWS_AS(packet_v2::Packet(ping_data), std::length_error);
428  REQUIRE_THROWS_WITH(
429  packet_v2::Packet(ping_data),
430  "Packet is 25 bytes, should be 26 bytes.");
431  // SET_MODE (target system only, no target component).
432  auto set_mode_data = to_vector(set_mode);
433  set_mode_data.push_back(0x00);
434  REQUIRE_THROWS_AS(packet_v2::Packet(set_mode_data), std::length_error);
435  REQUIRE_THROWS_WITH(
436  packet_v2::Packet(set_mode_data),
437  "Packet is 19 bytes, should be 18 bytes.");
438  // PARAM_REQUEST_READ (trimmed out, 0.0, system/component).
439  auto mission_set_current_data = to_vector(mission_set_current);
440  mission_set_current_data.pop_back();
441  REQUIRE_THROWS_AS(
442  packet_v2::Packet(mission_set_current_data), std::length_error);
443  REQUIRE_THROWS_WITH(
444  packet_v2::Packet(mission_set_current_data),
445  "Packet is 13 bytes, should be 14 bytes.");
446  // ENCAPSULATED_DATA (longest packet).
447  auto encapsulated_data_data = to_vector(encapsulated_data);
448  encapsulated_data_data.push_back(0x00);
449  REQUIRE_THROWS_AS(
450  packet_v2::Packet(encapsulated_data_data), std::length_error);
451  REQUIRE_THROWS_WITH(
452  packet_v2::Packet(encapsulated_data_data),
453  "Packet is 268 bytes, should be 267 bytes.");
454  // PARAM_EXT_REQUEST_LIST (message ID beyond 255).
455  auto param_ext_request_list_data = to_vector(param_ext_request_list);
456  param_ext_request_list_data.pop_back();
457  REQUIRE_THROWS_AS(
458  packet_v2::Packet(param_ext_request_list_data), std::length_error);
459  REQUIRE_THROWS_WITH(
460  packet_v2::Packet(param_ext_request_list_data),
461  "Packet is 13 bytes, should be 14 bytes.");
462  }
463  SECTION("And ensures the packet is the correct length (with signature).")
464  {
465  // HEARTBEAT (no target system/component).
466  auto heartbeat_data = to_vector_with_sig(heartbeat);
467  heartbeat_data.push_back(0x00);
468  REQUIRE_THROWS_AS(packet_v2::Packet(heartbeat_data), std::length_error);
469  REQUIRE_THROWS_WITH(
470  packet_v2::Packet(heartbeat_data),
471  "Signed packet is 35 bytes, should be 34 bytes.");
472  // PING (with target system/component).
473  auto ping_data = to_vector_with_sig(ping);
474  ping_data.pop_back();
475  REQUIRE_THROWS_AS(packet_v2::Packet(ping_data), std::length_error);
476  REQUIRE_THROWS_WITH(
477  packet_v2::Packet(ping_data),
478  "Signed packet is 38 bytes, should be 39 bytes.");
479  // SET_MODE (target system only, no target component).
480  auto set_mode_data = to_vector_with_sig(set_mode);
481  set_mode_data.push_back(0x00);
482  REQUIRE_THROWS_AS(packet_v2::Packet(set_mode_data), std::length_error);
483  REQUIRE_THROWS_WITH(
484  packet_v2::Packet(set_mode_data),
485  "Signed packet is 32 bytes, should be 31 bytes.");
486  // PARAM_REQUEST_READ (trimmed out, 0.0, system/component).
487  auto mission_set_current_data = to_vector_with_sig(mission_set_current);
488  mission_set_current_data.pop_back();
489  REQUIRE_THROWS_AS(
490  packet_v2::Packet(mission_set_current_data), std::length_error);
491  REQUIRE_THROWS_WITH(
492  packet_v2::Packet(mission_set_current_data),
493  "Signed packet is 26 bytes, should be 27 bytes.");
494  // ENCAPSULATED_DATA (longest packet).
495  auto encapsulated_data_data = to_vector_with_sig(encapsulated_data);
496  encapsulated_data_data.push_back(0x00);
497  REQUIRE_THROWS_AS(
498  packet_v2::Packet(encapsulated_data_data), std::length_error);
499  REQUIRE_THROWS_WITH(
500  packet_v2::Packet(encapsulated_data_data),
501  "Signed packet is 281 bytes, should be 280 bytes.");
502  // PARAM_EXT_REQUEST_LIST (message ID beyond 255).
503  auto param_ext_request_list_data =
504  to_vector_with_sig(param_ext_request_list);
505  param_ext_request_list_data.pop_back();
506  REQUIRE_THROWS_AS(
507  packet_v2::Packet(param_ext_request_list_data), std::length_error);
508  REQUIRE_THROWS_WITH(
509  packet_v2::Packet(param_ext_request_list_data),
510  "Signed packet is 26 bytes, should be 27 bytes.");
511  }
512 }
513 
514 
515 TEST_CASE("packet_v2::Packet's are comparable.", "[packet_v2::Packet]")
516 {
517  SECTION("with ==")
518  {
519  REQUIRE(
520  packet_v2::Packet(to_vector(PingV2())) ==
521  packet_v2::Packet(to_vector(PingV2())));
522  REQUIRE_FALSE(
523  packet_v2::Packet(to_vector(PingV2())) ==
524  packet_v2::Packet(to_vector(SetModeV2())));
525  REQUIRE_FALSE(
526  packet_v2::Packet(to_vector(PingV2())) ==
527  packet_v2::Packet(to_vector_with_sig(PingV2())));
528  }
529  SECTION("with !=")
530  {
531  REQUIRE(
532  packet_v2::Packet(to_vector(PingV2())) !=
533  packet_v2::Packet(to_vector(SetModeV2())));
534  REQUIRE(
535  packet_v2::Packet(to_vector(PingV2())) !=
536  packet_v2::Packet(to_vector_with_sig(PingV2())));
537  REQUIRE_FALSE(
538  packet_v2::Packet(to_vector(PingV2())) !=
539  packet_v2::Packet(to_vector(PingV2())));
540  }
541 }
542 
543 
544 TEST_CASE("packet_v2::Packet's are copyable.", "[packet_v2::Packet]")
545 {
546  packet_v2::Packet original(to_vector(PingV2()));
547  packet_v2::Packet copy(original);
548  REQUIRE(copy == packet_v2::Packet(to_vector(PingV2())));
549 }
550 
551 
552 TEST_CASE("packet_v2::Packet's are movable.", "[packet_v2::Packet]")
553 {
554  packet_v2::Packet original(to_vector(PingV2()));
555  packet_v2::Packet moved(std::move(original));
556  REQUIRE(moved == packet_v2::Packet(to_vector(PingV2())));
557 }
558 
559 
560 TEST_CASE("packet_v2::Packet's are assignable.", "[Packet]")
561 {
562  packet_v2::Packet packet_a(to_vector(PingV2()));
563  packet_v2::Packet packet_b(to_vector(SetModeV2()));
564  REQUIRE(packet_a == packet_v2::Packet(to_vector(PingV2())));
565  packet_a = packet_b;
566  REQUIRE(packet_b == packet_v2::Packet(to_vector(SetModeV2())));
567 }
568 
569 
570 TEST_CASE("packet_v2::Packet's are assignable (by move semantics).", "[Packet]")
571 {
572  packet_v2::Packet packet_a(to_vector(PingV2()));
573  packet_v2::Packet packet_b(to_vector(SetModeV2()));
574  REQUIRE(packet_a == packet_v2::Packet(to_vector(PingV2())));
576  REQUIRE(packet_b == packet_v2::Packet(to_vector(SetModeV2())));
577 }
578 
579 
580 TEST_CASE("packet_v2::Packet's contain raw packet data and make it accessible.",
581  "[packet_v2::Packet]")
582 {
583  auto heartbeat = to_vector_with_sig(HeartbeatV2());
584  auto ping = to_vector(PingV2());
585  auto set_mode = to_vector_with_sig(SetModeV2());
586  auto mission_set_current = to_vector(MissionSetCurrentV2());
587  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
588  auto param_ext_request_list = to_vector_with_sig(ParamExtRequestListV2());
589  REQUIRE(packet_v2::Packet(heartbeat).data() == heartbeat);
590  REQUIRE(packet_v2::Packet(ping).data() == ping);
591  REQUIRE(packet_v2::Packet(set_mode).data() == set_mode);
592  REQUIRE(
593  packet_v2::Packet(mission_set_current).data() == mission_set_current);
594  REQUIRE(
595  packet_v2::Packet(encapsulated_data).data() == encapsulated_data);
596  REQUIRE(
597  packet_v2::Packet(param_ext_request_list).data() ==
598  param_ext_request_list);
599 }
600 
601 
602 TEST_CASE("packet_v2::Packet's have a version.", "[packet_v2::Packet]")
603 {
604  auto heartbeat = to_vector_with_sig(HeartbeatV2());
605  auto ping = to_vector(PingV2());
606  auto set_mode = to_vector_with_sig(SetModeV2());
607  auto mission_set_current = to_vector(MissionSetCurrentV2());
608  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
609  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
610  // All should read Packet::V2 (0x0200) for v2.0.
611  REQUIRE(packet_v2::Packet(heartbeat).version() == Packet::V2);
612  REQUIRE(packet_v2::Packet(ping).version() == Packet::V2);
613  REQUIRE(packet_v2::Packet(set_mode).version() == Packet::V2);
614  REQUIRE(packet_v2::Packet(mission_set_current).version() == 0x200);
615  REQUIRE(packet_v2::Packet(encapsulated_data).version() == 0x200);
616  REQUIRE(packet_v2::Packet(param_ext_request_list).version() == 0x200);
617 }
618 
619 
620 TEST_CASE("packet_v2::Packet's have an ID.", "[packet_v2::Packet]")
621 {
622  auto heartbeat = to_vector_with_sig(HeartbeatV2());
623  auto ping = to_vector(PingV2());
624  auto set_mode = to_vector_with_sig(SetModeV2());
625  auto mission_set_current = to_vector(MissionSetCurrentV2());
626  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
627  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
628  REQUIRE(packet_v2::Packet(heartbeat).id() == 0);
629  REQUIRE(packet_v2::Packet(ping).id() == 4);
630  REQUIRE(packet_v2::Packet(set_mode).id() == 11);
631  REQUIRE(packet_v2::Packet(mission_set_current).id() == 41);
632  REQUIRE(packet_v2::Packet(encapsulated_data).id() == 131);
633  REQUIRE(packet_v2::Packet(param_ext_request_list).id() == 321);
634 }
635 
636 
637 TEST_CASE("packet_v2::Packet's have a name.", "[packet_v2::Packet]")
638 {
639  auto heartbeat = to_vector_with_sig(HeartbeatV2());
640  auto ping = to_vector(PingV2());
641  auto set_mode = to_vector_with_sig(SetModeV2());
642  auto mission_set_current = to_vector(MissionSetCurrentV2());
643  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
644  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
645  REQUIRE(packet_v2::Packet(heartbeat).name() == "HEARTBEAT");
646  REQUIRE(packet_v2::Packet(ping).name() == "PING");
647  REQUIRE(packet_v2::Packet(set_mode).name() == "SET_MODE");
648  REQUIRE(
649  packet_v2::Packet(mission_set_current).name() == "MISSION_SET_CURRENT");
650  REQUIRE(packet_v2::Packet(encapsulated_data).name() == "ENCAPSULATED_DATA");
651  REQUIRE(
652  packet_v2::Packet(param_ext_request_list).name() ==
653  "PARAM_EXT_REQUEST_LIST");
654 }
655 
656 
657 TEST_CASE("packet_v2::Packet's have a source address.", "[packet_v2::Packet]")
658 {
659  auto heartbeat = to_vector_with_sig(HeartbeatV2());
660  auto ping = to_vector(PingV2());
661  auto set_mode = to_vector_with_sig(SetModeV2());
662  auto mission_set_current = to_vector(MissionSetCurrentV2());
663  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
664  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
665  REQUIRE(packet_v2::Packet(heartbeat).source() == MAVAddress("127.1"));
666  REQUIRE(packet_v2::Packet(ping).source() == MAVAddress("192.168"));
667  REQUIRE(packet_v2::Packet(set_mode).source() == MAVAddress("172.0"));
668  REQUIRE(
669  packet_v2::Packet(mission_set_current).source() == MAVAddress("255.0"));
670  REQUIRE(
671  packet_v2::Packet(encapsulated_data).source() == MAVAddress("224.255"));
672  REQUIRE(
673  packet_v2::Packet(param_ext_request_list).source() ==
674  MAVAddress("0.255"));
675 }
676 
677 
678 TEST_CASE("packet_v2::Packet's optionally have a destination address.",
679  "[packet_v2::Packet]")
680 {
681  auto heartbeat = to_vector_with_sig(HeartbeatV2());
682  auto ping = to_vector(PingV2());
683  auto set_mode = to_vector_with_sig(SetModeV2());
684  auto mission_set_current = to_vector(MissionSetCurrentV2());
685  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
686  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
687  REQUIRE_THROWS_AS(
688  packet_v2::Packet(heartbeat).dest().value(), std::bad_optional_access);
689  REQUIRE(packet_v2::Packet(ping).dest().value() == MAVAddress("127.1"));
690  REQUIRE(packet_v2::Packet(set_mode).dest().value() == MAVAddress("123.0"));
691  REQUIRE(
692  packet_v2::Packet(mission_set_current).dest().value() ==
693  MAVAddress("0.0"));
694  REQUIRE_THROWS_AS(
695  packet_v2::Packet(encapsulated_data).dest().value(),
696  std::bad_optional_access);
697  REQUIRE(
698  packet_v2::Packet(param_ext_request_list).dest().value() ==
699  MAVAddress("32.64"));
700 }
701 
702 
703 TEST_CASE("packet_v2::Packet's optionally have a source connection.",
704  "[packet_v2::Packet]")
705 {
706  auto heartbeat = packet_v2::Packet(to_vector(HeartbeatV2()));
707  SECTION("Defaults to nullptr.")
708  {
709  REQUIRE(heartbeat.connection() == nullptr);
710  }
711  SECTION("Can be set with the 'connection' method.")
712  {
713  fakeit::Mock<Filter> mock_filter;
714  auto filter = mock_shared(mock_filter);
715  auto conn = std::make_shared<Connection>("SOURCE", filter);
716  heartbeat.connection(conn);
717  REQUIRE(heartbeat.connection() != nullptr);
718  REQUIRE(heartbeat.connection() == conn);
719  REQUIRE(str(*heartbeat.connection()) == "SOURCE");
720  }
721 }
722 
723 
724 TEST_CASE("packet_v2::Packet's are printable.", "[packet_v2::Packet]")
725 {
726  auto heartbeat = to_vector_with_sig(HeartbeatV2());
727  auto ping = to_vector(PingV2());
728  auto set_mode = to_vector_with_sig(SetModeV2());
729  auto mission_set_current = to_vector(MissionSetCurrentV2());
730  auto encapsulated_data = to_vector_with_sig(EncapsulatedDataV2());
731  auto param_ext_request_list = to_vector(ParamExtRequestListV2());
732  REQUIRE(
734  "HEARTBEAT (#0) from 127.1 (v2.0)");
735  REQUIRE(
737  "PING (#4) from 192.168 to 127.1 (v2.0)");
738  REQUIRE(
739  str(packet_v2::Packet(set_mode)) ==
740  "SET_MODE (#11) from 172.0 to 123.0 (v2.0)");
741  REQUIRE(
742  str(packet_v2::Packet(mission_set_current)) ==
743  "MISSION_SET_CURRENT (#41) from 255.0 to 0.0 (v2.0)");
744  REQUIRE(
745  str(packet_v2::Packet(encapsulated_data)) ==
746  "ENCAPSULATED_DATA (#131) from 224.255 (v2.0)");
747  REQUIRE(
748  str(packet_v2::Packet(param_ext_request_list)) ==
749  "PARAM_EXT_REQUEST_LIST (#321) from 0.255 to 32.64 (v2.0)");
750 }
std::string str(const T &object)
Definition: utility.hpp:128
bool packet_complete(const std::vector< uint8_t > &data)
bool header_complete(const std::vector< uint8_t > &data)
packet_v2::Packet packet_b(to_vector(SetModeV2()))
TEST_CASE("'packet_v2::header_complete' determines whether the given bytes " "at least represent a complete header.", "[packet_v2]")
const struct mavlink::v2_header * header(const std::vector< uint8_t > &data)
MAVLink Version 2.0.
Definition: Packet.hpp:50
def heartbeat(mav)
Definition: logger.py:42
std::shared_ptr< T > mock_shared(fakeit::Mock< T > &mock)
Definition: common.hpp:33
auto ping
Definition: test_Call.cpp:229
bool is_signed(const std::vector< uint8_t > &data)