mavtables  0.2.1
MAVLink router and firewall.
test_Packet.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 <cstdint>
19 #include <memory>
20 #include <optional>
21 #include <string>
22 #include <utility>
23 #include <vector>
24 
25 #include <catch.hpp>
26 #include <fakeit.hpp>
27 
28 #include "Connection.hpp"
29 #include "Filter.hpp"
30 #include "MAVAddress.hpp"
31 #include "Packet.hpp"
32 #include "utility.hpp"
33 
34 #include "common.hpp"
35 #include "common_Packet.hpp"
36 
37 
38 namespace
39 {
40 
41 #ifdef __clang__
42  #pragma clang diagnostic push
43  #pragma clang diagnostic ignored "-Wweak-vtables"
44 #endif
45 
46  // Subclass of Packet used for testing the abstract class Packet.
47  class PacketTestClass : public Packet
48  {
49  public:
50  PacketTestClass(const PacketTestClass &other) = default;
51  PacketTestClass(PacketTestClass &&other) = default;
52  PacketTestClass(std::vector<uint8_t> data)
53  : Packet(std::move(data))
54  {
55  }
56  // LCOV_EXCL_START
57  ~PacketTestClass() = default;
58  // LCOV_EXCL_STOP
59  virtual ::Packet::Version version() const
60  {
61  return ::Packet::V1;
62  }
63  virtual unsigned long id() const
64  {
65  return 42;
66  }
67  virtual std::string name() const
68  {
69  return "MISSION_CURRENT";
70  }
71  virtual MAVAddress source() const
72  {
73  return MAVAddress("3.14");
74  }
75  virtual std::optional<MAVAddress> dest() const
76  {
77  return MAVAddress("2.71");
78  }
79  PacketTestClass &operator=(const PacketTestClass &other) = default;
80  PacketTestClass &operator=(PacketTestClass &&other) = default;
81  };
82 
83 #ifdef __clang__
84  #pragma clang diagnostic pop
85 #endif
86 
87 }
88 
89 
90 TEST_CASE("Packet's can be constructed.", "[Packet]")
91 {
92  std::vector<uint8_t> data = {0, 7, 7, 3, 4};
93  REQUIRE_NOTHROW(PacketTestClass({}));
94  REQUIRE_NOTHROW(PacketTestClass({1, 3, 3, 7}));
95  REQUIRE_NOTHROW(PacketTestClass(data));
96 }
97 
98 
99 TEST_CASE("Packet's are comparable.", "[Packet]")
100 {
101  SECTION("with ==")
102  {
103  REQUIRE(PacketTestClass({1, 3, 3, 7}) == PacketTestClass({1, 3, 3, 7}));
104  REQUIRE_FALSE(
105  PacketTestClass({1, 3, 3, 7}) == PacketTestClass({0, 7, 7, 3, 4}));
106  }
107  SECTION("with !=")
108  {
109  REQUIRE(
110  PacketTestClass({1, 3, 3, 7}) != PacketTestClass({0, 7, 7, 3, 4}));
111  REQUIRE_FALSE(
112  PacketTestClass({1, 3, 3, 7}) != PacketTestClass({1, 3, 3, 7}));
113  }
114 }
115 
116 
117 TEST_CASE("Packet's are copyable.", "[Packet]")
118 {
119  PacketTestClass original({1, 3, 3, 7});
120  PacketTestClass copy(original);
121  REQUIRE(copy == PacketTestClass({1, 3, 3, 7}));
122 }
123 
124 
125 TEST_CASE("Packet's are movable.", "[Packet]")
126 {
127  PacketTestClass original({1, 3, 3, 7});
128  PacketTestClass moved(std::move(original));
129  REQUIRE(moved == PacketTestClass({1, 3, 3, 7}));
130 }
131 
132 
133 TEST_CASE("Packet's are assignable.", "[Packet]")
134 {
135  PacketTestClass packet_a({1, 3, 3, 7});
136  PacketTestClass packet_b({0, 7, 7, 3, 4});
137  REQUIRE(packet_a == PacketTestClass({1, 3, 3, 7}));
138  packet_a = packet_b;
139  REQUIRE(packet_a == PacketTestClass({0, 7, 7, 3, 4}));
140 }
141 
142 
143 TEST_CASE("Packet's are assignable (by move semantics).", "[Packet]")
144 {
145  PacketTestClass packet_a({1, 3, 3, 7});
146  PacketTestClass packet_b({0, 7, 7, 3, 4});
147  REQUIRE(packet_a == PacketTestClass({1, 3, 3, 7}));
148  packet_a = std::move(packet_b);
149  REQUIRE(packet_a == PacketTestClass({0, 7, 7, 3, 4}));
150 }
151 
152 
153 TEST_CASE("Packet's contain raw packet data and make it accessible.",
154  "[Packet]")
155 {
156  REQUIRE(
157  PacketTestClass({1, 3, 3, 7}).data() ==
158  std::vector<uint8_t>({1, 3, 3, 7}));
159  REQUIRE_FALSE(
160  PacketTestClass({1, 3, 3, 7}).data() ==
161  std::vector<uint8_t>({1, 0, 5, 3}));
162 }
163 
164 
165 TEST_CASE("Packet's have a version.", "[Packet]")
166 {
167  REQUIRE(PacketTestClass({}).version() == Packet::V1);
168 }
169 
170 
171 TEST_CASE("Packet's have an ID.", "[Packet]")
172 {
173  REQUIRE(PacketTestClass({}).id() == 42);
174 }
175 
176 
177 TEST_CASE("Packet's have a name.", "[Packet]")
178 {
179  REQUIRE(PacketTestClass({}).name() == "MISSION_CURRENT");
180 }
181 
182 
183 TEST_CASE("Packet's have a source address.", "[Packet]")
184 {
185  REQUIRE(PacketTestClass({}).source() == MAVAddress("3.14"));
186 }
187 
188 
189 TEST_CASE("Packet's optionally have a destination address.", "[Packet]")
190 {
191  REQUIRE(PacketTestClass({}).dest().value() == MAVAddress("2.71"));
192 }
193 
194 
195 TEST_CASE("Packet's optionally have a source connection.", "[Packet]")
196 {
197  SECTION("Defaults to nullptr.")
198  {
199  REQUIRE(PacketTestClass({}).connection() == nullptr);
200  }
201  SECTION("Can be set with the 'connection' method.")
202  {
203  fakeit::Mock<Filter> mock_filter;
204  auto filter = mock_shared(mock_filter);
205  auto conn = std::make_shared<Connection>("SOURCE", filter);
206  PacketTestClass packet({});
207  packet.connection(conn);
208  REQUIRE(packet.connection() != nullptr);
209  REQUIRE(packet.connection() == conn);
210  REQUIRE(str(*packet.connection()) == "SOURCE");
211  }
212 }
213 
214 
215 TEST_CASE("Packet's are printable.", "[Packet]")
216 {
217  REQUIRE(
218  str(PacketTestClass({})) ==
219  "MISSION_CURRENT (#42) from 3.14 to 2.71 (v1.0)");
220 }
std::string str(const T &object)
Definition: utility.hpp:128
Packet & operator=(const Packet &other)=default
virtual unsigned long id() const =0
PacketTestClass packet_b({0, 7, 7, 3, 4})
STL namespace.
virtual std::optional< MAVAddress > dest() const =0
virtual std::string name() const =0
TEST_CASE("Packet's can be constructed.", "[Packet]")
Definition: test_Packet.cpp:90
virtual MAVAddress source() const =0
std::shared_ptr< T > mock_shared(fakeit::Mock< T > &mock)
Definition: common.hpp:33
virtual Version version() const =0
packet_a
MAVLink Version 1.0.
Definition: Packet.hpp:49