mavtables  0.2.1
MAVLink router and firewall.
test_MAVSubnet.cpp
Go to the documentation of this file.
1 // MAVLink router and firewall.
2 // Copyright (C) 2017-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 <stdexcept>
19 #include <utility>
20 
21 #include <catch.hpp>
22 
23 #include "MAVAddress.hpp"
24 #include "MAVSubnet.hpp"
25 #include "utility.hpp"
26 
27 
28 TEST_CASE("MAVSubnet's are comparable.", "[MAVSubnet]")
29 {
30  SECTION("with ==")
31  {
32  REQUIRE(MAVSubnet(MAVAddress(0x0000), 0x0000) ==
33  MAVSubnet(MAVAddress(0x0000), 0x0000));
34  REQUIRE(MAVSubnet(MAVAddress(0x1234), 0x5678) ==
35  MAVSubnet(MAVAddress(0x1234), 0x5678));
36  REQUIRE(MAVSubnet(MAVAddress(0xFFFF), 0xFFFF) ==
37  MAVSubnet(MAVAddress(0xFFFF), 0xFFFF));
38  REQUIRE_FALSE(MAVSubnet(MAVAddress(0x0000), 0x0000) ==
39  MAVSubnet(MAVAddress(0x0001), 0x0000));
40  REQUIRE_FALSE(MAVSubnet(MAVAddress(0x0000), 0x0000) ==
41  MAVSubnet(MAVAddress(0x0000), 0x0001));
42  REQUIRE_FALSE(MAVSubnet(MAVAddress(0x1234), 0x5678) ==
43  MAVSubnet(MAVAddress(0x1235), 0x5678));
44  REQUIRE_FALSE(MAVSubnet(MAVAddress(0x1234), 0x5678) ==
45  MAVSubnet(MAVAddress(0x1234), 0x5679));
46  REQUIRE_FALSE(MAVSubnet(MAVAddress(0xFFFF), 0xFFFF) ==
47  MAVSubnet(MAVAddress(0xFFFE), 0xFFFF));
48  REQUIRE_FALSE(MAVSubnet(MAVAddress(0xFFFF), 0xFFFF) ==
49  MAVSubnet(MAVAddress(0xFFFF), 0xFFFE));
50  }
51  SECTION("with !=")
52  {
53  REQUIRE(MAVSubnet(MAVAddress(0x0000), 0x0000) !=
54  MAVSubnet(MAVAddress(0x0001), 0x0000));
55  REQUIRE(MAVSubnet(MAVAddress(0x0000), 0x0000) !=
56  MAVSubnet(MAVAddress(0x0000), 0x0001));
57  REQUIRE(MAVSubnet(MAVAddress(0x1234), 0x5678) !=
58  MAVSubnet(MAVAddress(0x1235), 0x5678));
59  REQUIRE(MAVSubnet(MAVAddress(0x1234), 0x5678) !=
60  MAVSubnet(MAVAddress(0x1234), 0x5679));
61  REQUIRE(MAVSubnet(MAVAddress(0xFFFF), 0xFFFF) !=
62  MAVSubnet(MAVAddress(0xFFFE), 0xFFFF));
63  REQUIRE(MAVSubnet(MAVAddress(0xFFFF), 0xFFFF) !=
64  MAVSubnet(MAVAddress(0xFFFF), 0xFFFE));
65  REQUIRE_FALSE(MAVSubnet(MAVAddress(0x0000), 0x0000) !=
66  MAVSubnet(MAVAddress(0x0000), 0x0000));
67  REQUIRE_FALSE(MAVSubnet(MAVAddress(0x1234), 0x5678) !=
68  MAVSubnet(MAVAddress(0x1234), 0x5678));
69  REQUIRE_FALSE(MAVSubnet(MAVAddress(0xFFFF), 0xFFFF) !=
70  MAVSubnet(MAVAddress(0xFFFF), 0xFFFF));
71  }
72 }
73 
74 
75 TEST_CASE("MAVSubnet's can be constructed from a MAVLink address "
76  "and a numeric mask.", "[MAVSubnet]")
77 {
78  REQUIRE(MAVSubnet(MAVAddress(0x0000), 0x0000) ==
79  MAVSubnet(MAVAddress(0x0000), 0x0000));
80  REQUIRE(MAVSubnet(MAVAddress(0x1234), 0x5678) ==
81  MAVSubnet(MAVAddress(0x1234), 0x5678));
82  REQUIRE(MAVSubnet(MAVAddress(0xFFFF), 0xFFFF) ==
83  MAVSubnet(MAVAddress(0xFFFF), 0xFFFF));
84  SECTION("And ensures the mask is within range (0x0000 - 0xFFFF).")
85  {
86  REQUIRE_THROWS_AS(
87  MAVSubnet(MAVAddress(0x0000),
88  static_cast<unsigned int>(0x0000 - 1)),
89  std::out_of_range);
90  REQUIRE_THROWS_AS(
91  MAVSubnet(MAVAddress(0x0000), 0xFFFF + 1), std::out_of_range);
92  }
93 }
94 
95 
96 TEST_CASE("MAVSubnet's can be constructed from a MAVLink address, "
97  "system mask, and component mask.", "[MAVSubnet]")
98 {
99  REQUIRE(MAVSubnet(MAVAddress(0x0000), 0, 0) ==
100  MAVSubnet(MAVAddress(0x0000), 0));
101  REQUIRE(MAVSubnet(MAVAddress(0x0000), 255, 0) ==
102  MAVSubnet(MAVAddress(0x0000), 0xFF00));
103  REQUIRE(MAVSubnet(MAVAddress(0x0000), 0, 255) ==
104  MAVSubnet(MAVAddress(0x0000), 0x00FF));
105  REQUIRE(MAVSubnet(MAVAddress(0xFFFF), 255, 255) ==
106  MAVSubnet(MAVAddress(0xFFFF), 0xFFFF));
107  REQUIRE(MAVSubnet(MAVAddress(0x1234), 64, 128) ==
108  MAVSubnet(MAVAddress(0x1234), 0x4080));
109  REQUIRE(MAVSubnet(MAVAddress(0x1234), 128, 64) ==
110  MAVSubnet(MAVAddress(0x1234), 0x8040));
111  SECTION("And ensures the system and component masks are within range "
112  "(0x00 - 0xFF).")
113  {
114  auto addr = MAVAddress(0x0000);
115  // Errors
116  REQUIRE_THROWS_AS(
117  MAVSubnet(addr, static_cast<unsigned int>(-1), 0),
118  std::out_of_range);
119  REQUIRE_THROWS_AS(
120  MAVSubnet(addr, 0, static_cast<unsigned int>(-1)),
121  std::out_of_range);
122  REQUIRE_THROWS_AS(
123  MAVSubnet(addr,
124  static_cast<unsigned int>(-1),
125  static_cast<unsigned int>(-1)),
126  std::out_of_range);
127  REQUIRE_THROWS_AS(MAVSubnet(addr, 256, 255), std::out_of_range);
128  REQUIRE_THROWS_AS(MAVSubnet(addr, 255, 256), std::out_of_range);
129  REQUIRE_THROWS_AS(MAVSubnet(addr, 256, 256), std::out_of_range);
130  // Error messages.
131  REQUIRE_THROWS_WITH(
132  MAVSubnet(addr, 256, 255),
133  "System mask (0x100) is outside of the allowed range "
134  "(0x00 - 0xFF).");
135  REQUIRE_THROWS_WITH(
136  MAVSubnet(addr, 255, 256),
137  "Component mask (0x100) is outside of the allowed range "
138  "(0x00 - 0xFF).");
139  }
140 }
141 
142 
143 TEST_CASE("MAVSubnet's can be constructed from strings.", "[MAVSubnet]")
144 {
145  auto addr = MAVAddress(255, 16);
146  SECTION("Using no mask (exact address).")
147  {
148  REQUIRE(MAVSubnet("255.16") == MAVSubnet(addr, 255, 255));
149  }
150  SECTION("Using long notation.")
151  {
152  REQUIRE(MAVSubnet("255.16:123.234") == MAVSubnet(addr, 123, 234));
153  REQUIRE(MAVSubnet("255.16:0.0") == MAVSubnet(addr, 0, 0));
154  REQUIRE(MAVSubnet("255.16:128.0") == MAVSubnet(addr, 128, 0));
155  REQUIRE(MAVSubnet("255.16:0.240") == MAVSubnet(addr, 0, 240));
156  REQUIRE(MAVSubnet("255.16:128.240") == MAVSubnet(addr, 128, 240));
157  }
158  SECTION("Using forward slash notation.")
159  {
160  REQUIRE(MAVSubnet("255.16/0") == MAVSubnet(addr, 0b0000000000000000));
161  REQUIRE(MAVSubnet("255.16/1") == MAVSubnet(addr, 0b1000000000000000));
162  REQUIRE(MAVSubnet("255.16/2") == MAVSubnet(addr, 0b1100000000000000));
163  REQUIRE(MAVSubnet("255.16/3") == MAVSubnet(addr, 0b1110000000000000));
164  REQUIRE(MAVSubnet("255.16/4") == MAVSubnet(addr, 0b1111000000000000));
165  REQUIRE(MAVSubnet("255.16/5") == MAVSubnet(addr, 0b1111100000000000));
166  REQUIRE(MAVSubnet("255.16/6") == MAVSubnet(addr, 0b1111110000000000));
167  REQUIRE(MAVSubnet("255.16/7") == MAVSubnet(addr, 0b1111111000000000));
168  REQUIRE(MAVSubnet("255.16/8") == MAVSubnet(addr, 0b1111111100000000));
169  REQUIRE(MAVSubnet("255.16/9") == MAVSubnet(addr, 0b1111111110000000));
170  REQUIRE(MAVSubnet("255.16/10") == MAVSubnet(addr, 0b1111111111000000));
171  REQUIRE(MAVSubnet("255.16/11") == MAVSubnet(addr, 0b1111111111100000));
172  REQUIRE(MAVSubnet("255.16/12") == MAVSubnet(addr, 0b1111111111110000));
173  REQUIRE(MAVSubnet("255.16/13") == MAVSubnet(addr, 0b1111111111111000));
174  REQUIRE(MAVSubnet("255.16/14") == MAVSubnet(addr, 0b1111111111111100));
175  REQUIRE(MAVSubnet("255.16/15") == MAVSubnet(addr, 0b1111111111111110));
176  REQUIRE(MAVSubnet("255.16/16") == MAVSubnet(addr, 0b1111111111111111));
177  }
178  SECTION("Using backslash notation.")
179  {
180  REQUIRE(MAVSubnet("255.16\\0") == MAVSubnet(addr, 0b0000000000000000));
181  REQUIRE(MAVSubnet("255.16\\1") == MAVSubnet(addr, 0b0000000010000000));
182  REQUIRE(MAVSubnet("255.16\\2") == MAVSubnet(addr, 0b0000000011000000));
183  REQUIRE(MAVSubnet("255.16\\3") == MAVSubnet(addr, 0b0000000011100000));
184  REQUIRE(MAVSubnet("255.16\\4") == MAVSubnet(addr, 0b0000000011110000));
185  REQUIRE(MAVSubnet("255.16\\5") == MAVSubnet(addr, 0b0000000011111000));
186  REQUIRE(MAVSubnet("255.16\\6") == MAVSubnet(addr, 0b0000000011111100));
187  REQUIRE(MAVSubnet("255.16\\7") == MAVSubnet(addr, 0b0000000011111110));
188  REQUIRE(MAVSubnet("255.16\\8") == MAVSubnet(addr, 0b0000000011111111));
189  }
190  SECTION("And ensures the subnet string is valid.")
191  {
192  // Errors
193  REQUIRE_THROWS_AS(MAVSubnet("255.16 255.256"), std::invalid_argument);
194  REQUIRE_THROWS_AS(MAVSubnet("255.16-256.255"), std::invalid_argument);
195  REQUIRE_THROWS_AS(MAVSubnet("255.16+256.255"), std::invalid_argument);
196  REQUIRE_THROWS_AS(MAVSubnet("255.16:1"), std::invalid_argument);
197  REQUIRE_THROWS_AS(MAVSubnet("255.16:1."), std::invalid_argument);
198  REQUIRE_THROWS_AS(MAVSubnet("255.16:1.2."), std::invalid_argument);
199  REQUIRE_THROWS_AS(MAVSubnet("255.16:1.2.3"), std::invalid_argument);
200  REQUIRE_THROWS_AS(MAVSubnet("255.16:a.2.3"), std::invalid_argument);
201  REQUIRE_THROWS_AS(MAVSubnet("255.16:1.b.3"), std::invalid_argument);
202  REQUIRE_THROWS_AS(MAVSubnet("255.16:1.2.c"), std::invalid_argument);
203  REQUIRE_THROWS_AS(MAVSubnet("255.16:+1.0"), std::invalid_argument);
204  REQUIRE_THROWS_AS(MAVSubnet("255.16:0.+1"), std::invalid_argument);
205  REQUIRE_THROWS_AS(MAVSubnet("255.16:-1.0"), std::invalid_argument);
206  REQUIRE_THROWS_AS(MAVSubnet("255.16:0.-1"), std::invalid_argument);
207  // Error messages.
208  REQUIRE_THROWS_WITH(
209  MAVSubnet("255.16 255.256"),
210  "Invalid MAVLink subnet: \"255.16 255.256\".");
211  REQUIRE_THROWS_WITH(
212  MAVSubnet("255.16-256.255"),
213  "Invalid MAVLink subnet: \"255.16-256.255\".");
214  REQUIRE_THROWS_WITH(
215  MAVSubnet("255.16+256.255"),
216  "Invalid MAVLink subnet: \"255.16+256.255\".");
217  REQUIRE_THROWS_WITH(
218  MAVSubnet("255.16:1"), "Invalid MAVLink subnet: \"255.16:1\".");
219  REQUIRE_THROWS_WITH(
220  MAVSubnet("255.16:1."), "Invalid MAVLink subnet: \"255.16:1.\".");
221  REQUIRE_THROWS_WITH(
222  MAVSubnet("255.16:1.2."),
223  "Invalid MAVLink subnet: \"255.16:1.2.\".");
224  REQUIRE_THROWS_WITH(
225  MAVSubnet("255.16:1.2.3"),
226  "Invalid MAVLink subnet: \"255.16:1.2.3\".");
227  REQUIRE_THROWS_WITH(
228  MAVSubnet("255.16:a.2.3"),
229  "Invalid MAVLink subnet: \"255.16:a.2.3\".");
230  REQUIRE_THROWS_WITH(
231  MAVSubnet("255.16:1.b.3"),
232  "Invalid MAVLink subnet: \"255.16:1.b.3\".");
233  REQUIRE_THROWS_WITH(
234  MAVSubnet("255.16:1.2.c"),
235  "Invalid MAVLink subnet: \"255.16:1.2.c\".");
236  REQUIRE_THROWS_WITH(
237  MAVSubnet("255.16:+1.0"),
238  "Invalid MAVLink subnet: \"255.16:+1.0\".");
239  REQUIRE_THROWS_WITH(
240  MAVSubnet("255.16:0.+1"),
241  "Invalid MAVLink subnet: \"255.16:0.+1\".");
242  REQUIRE_THROWS_WITH(
243  MAVSubnet("255.16:-1.0"),
244  "Invalid MAVLink subnet: \"255.16:-1.0\".");
245  REQUIRE_THROWS_WITH(
246  MAVSubnet("255.16:0.-1"),
247  "Invalid MAVLink subnet: \"255.16:0.-1\".");
248  }
249  SECTION("And ensures mask is within range.")
250  {
251  // Errors
252  REQUIRE_THROWS_AS(MAVSubnet("255.16:256.255"), std::out_of_range);
253  REQUIRE_THROWS_AS(MAVSubnet("255.16:255.256"), std::out_of_range);
254  // Error messages.
255  REQUIRE_THROWS_WITH(
256  MAVSubnet("255.16:256.255"),
257  "System ID (256) is outside of the allowed range (0 - 255).");
258  REQUIRE_THROWS_WITH(
259  MAVSubnet("255.16:255.256"),
260  "Component ID (256) is outside of the allowed range (0 - 255).");
261  }
262  SECTION("And ensures forward slash mask is within range.")
263  {
264  // Errors
265  REQUIRE_THROWS_AS(MAVSubnet("255.16/-1"), std::out_of_range);
266  REQUIRE_THROWS_AS(MAVSubnet("255.16/17"), std::out_of_range);
267  // Error messages.
268  REQUIRE_THROWS_WITH(
269  MAVSubnet("255.16/17"),
270  "Forward slash mask (17) is outside of allowed range (0 - 16).");
271  }
272  SECTION("And ensures backslash mask is within range.")
273  {
274  // Errors
275  REQUIRE_THROWS_AS(MAVSubnet("255.16/-1"), std::out_of_range);
276  REQUIRE_THROWS_AS(MAVSubnet("255.16\\-1"), std::out_of_range);
277  // Error messages.
278  REQUIRE_THROWS_WITH(
279  MAVSubnet("255.16\\9"),
280  "Backslash mask (9) is outside of allowed range (0 - 8).");
281  }
282 }
283 
284 
285 TEST_CASE("MAVSubnet's are copyable.", "[MAVSubnet]")
286 {
287  MAVSubnet subnet_a(MAVAddress(0x0000), 0, 0);
288  MAVSubnet subnet_b(MAVAddress(0xFFFF), 255, 255);
289  MAVSubnet subnet_a_copy = subnet_a;
290  MAVSubnet subnet_b_copy(subnet_b);
291  REQUIRE(&subnet_a != &subnet_a_copy);
292  REQUIRE(subnet_a == subnet_a_copy);
293  REQUIRE(&subnet_b != &subnet_b_copy);
294  REQUIRE(subnet_b == subnet_b_copy);
295 }
296 
297 
298 TEST_CASE("MAVSubnet's are movable.", "[MAVSubnet]")
299 {
300  MAVSubnet subnet_a(MAVAddress(0x0000), 0, 0);
301  MAVSubnet subnet_b(MAVAddress(0xFFFF), 255, 255);
302  MAVSubnet subnet_a_moved = std::move(subnet_a);
303  MAVSubnet subnet_b_moved(std::move(subnet_b));
304  REQUIRE(subnet_a_moved == MAVSubnet(MAVAddress(0x0000), 0, 0));
305  REQUIRE(subnet_b_moved == MAVSubnet(MAVAddress(0xFFFF), 255, 255));
306 }
307 
308 
309 TEST_CASE("MAVSubnet's are assignable.", "[MAVSubnet]")
310 {
311  MAVSubnet subnet_a(MAVAddress(0x0000), 0, 0);
312  MAVSubnet subnet_b(MAVAddress(0xFFFF), 255, 255);
313  REQUIRE(subnet_a == MAVSubnet(MAVAddress(0x0000), 0, 0));
314  subnet_a = subnet_b;
315  REQUIRE(subnet_a == MAVSubnet(MAVAddress(0xFFFF), 255, 255));
316 }
317 
318 
319 TEST_CASE("MAVSubnet's are assignable (by move semantics).", "[MAVSubnet]")
320 {
321  MAVSubnet subnet_a(MAVAddress(0x0000), 0, 0);
322  MAVSubnet subnet_b(MAVAddress(0xFFFF), 255, 255);
323  REQUIRE(subnet_a == MAVSubnet(MAVAddress(0x0000), 0, 0));
324  subnet_a = std::move(subnet_b);
325  REQUIRE(subnet_a == MAVSubnet(MAVAddress(0xFFFF), 255, 255));
326 }
327 
328 
329 TEST_CASE("MAVSubnet's are printable.", "[MAVSubnet]")
330 {
331  auto addr = MAVAddress(255, 16);
332  REQUIRE(str(MAVSubnet(addr, 123, 234)) == "255.16:123.234");
333  REQUIRE(str(MAVSubnet(addr, 128, 240)) == "255.16:128.240");
334  REQUIRE(str(MAVSubnet(addr, 0b0000000000000000)) == "255.16/0");
335  REQUIRE(str(MAVSubnet(addr, 0b1000000000000000)) == "255.16/1");
336  REQUIRE(str(MAVSubnet(addr, 0b1100000000000000)) == "255.16/2");
337  REQUIRE(str(MAVSubnet(addr, 0b1110000000000000)) == "255.16/3");
338  REQUIRE(str(MAVSubnet(addr, 0b1111000000000000)) == "255.16/4");
339  REQUIRE(str(MAVSubnet(addr, 0b1111100000000000)) == "255.16/5");
340  REQUIRE(str(MAVSubnet(addr, 0b1111110000000000)) == "255.16/6");
341  REQUIRE(str(MAVSubnet(addr, 0b1111111000000000)) == "255.16/7");
342  REQUIRE(str(MAVSubnet(addr, 0b1111111100000000)) == "255.16/8");
343  REQUIRE(str(MAVSubnet(addr, 0b1111111110000000)) == "255.16/9");
344  REQUIRE(str(MAVSubnet(addr, 0b1111111111000000)) == "255.16/10");
345  REQUIRE(str(MAVSubnet(addr, 0b1111111111100000)) == "255.16/11");
346  REQUIRE(str(MAVSubnet(addr, 0b1111111111110000)) == "255.16/12");
347  REQUIRE(str(MAVSubnet(addr, 0b1111111111111000)) == "255.16/13");
348  REQUIRE(str(MAVSubnet(addr, 0b1111111111111100)) == "255.16/14");
349  REQUIRE(str(MAVSubnet(addr, 0b1111111111111110)) == "255.16/15");
350  REQUIRE(str(MAVSubnet(addr, 0b1111111111111111)) == "255.16");
351  REQUIRE(str(MAVSubnet(addr, 0b0000000010000000)) == "255.16\\1");
352  REQUIRE(str(MAVSubnet(addr, 0b0000000011000000)) == "255.16\\2");
353  REQUIRE(str(MAVSubnet(addr, 0b0000000011100000)) == "255.16\\3");
354  REQUIRE(str(MAVSubnet(addr, 0b0000000011110000)) == "255.16\\4");
355  REQUIRE(str(MAVSubnet(addr, 0b0000000011111000)) == "255.16\\5");
356  REQUIRE(str(MAVSubnet(addr, 0b0000000011111100)) == "255.16\\6");
357  REQUIRE(str(MAVSubnet(addr, 0b0000000011111110)) == "255.16\\7");
358  REQUIRE(str(MAVSubnet(addr, 0b0000000011111111)) == "255.16\\8");
359 }
360 
361 
362 TEST_CASE("The 'contains' method determines if a MAVLink address "
363  "is in the subnet.",
364  "[MAVSubnet]")
365 {
366  REQUIRE(MAVSubnet("0.0:0.0").contains(MAVAddress("0.0")));
367  REQUIRE(MAVSubnet("0.0:0.0").contains(MAVAddress("255.255")));
368  REQUIRE(MAVSubnet("0.0:255.255").contains(MAVAddress("0.0")));
369  REQUIRE_FALSE(MAVSubnet("0.0:255.255").contains(MAVAddress("1.1")));
370  REQUIRE_FALSE(MAVSubnet("0.0:255.255").contains(MAVAddress("255.255")));
371  SECTION("With subnet 192.0/14")
372  {
373  MAVSubnet subnet("192.0/14");
374  REQUIRE(subnet.contains(MAVAddress("192.0")));
375  REQUIRE(subnet.contains(MAVAddress("192.1")));
376  REQUIRE(subnet.contains(MAVAddress("192.2")));
377  REQUIRE(subnet.contains(MAVAddress("192.3")));
378  REQUIRE_FALSE(subnet.contains(MAVAddress("192.4")));
379  REQUIRE_FALSE(subnet.contains(MAVAddress("192.5")));
380  REQUIRE_FALSE(subnet.contains(MAVAddress("192.255")));
381  REQUIRE_FALSE(subnet.contains(MAVAddress("191.0")));
382  REQUIRE_FALSE(subnet.contains(MAVAddress("193.1")));
383  REQUIRE_FALSE(subnet.contains(MAVAddress("0.2")));
384  REQUIRE_FALSE(subnet.contains(MAVAddress("255.3")));
385  }
386  SECTION("With subnet 192.0\\6")
387  {
388  MAVSubnet subnet("192.0\\6");
389  REQUIRE(subnet.contains(MAVAddress("192.0")));
390  REQUIRE(subnet.contains(MAVAddress("192.1")));
391  REQUIRE(subnet.contains(MAVAddress("192.2")));
392  REQUIRE(subnet.contains(MAVAddress("192.3")));
393  REQUIRE_FALSE(subnet.contains(MAVAddress("192.4")));
394  REQUIRE_FALSE(subnet.contains(MAVAddress("192.5")));
395  REQUIRE_FALSE(subnet.contains(MAVAddress("192.255")));
396  REQUIRE(subnet.contains(MAVAddress("191.0")));
397  REQUIRE(subnet.contains(MAVAddress("193.1")));
398  REQUIRE(subnet.contains(MAVAddress("0.2")));
399  REQUIRE(subnet.contains(MAVAddress("255.3")));
400  }
401 }
std::string str(const T &object)
Definition: utility.hpp:128
TEST_CASE("MAVSubnet's are comparable.", "[MAVSubnet]")
MAVSubnet subnet_b(MAVAddress(0xFFFF), 255, 255)
subnet_a
bool contains(const MAVAddress &address) const
Definition: MAVSubnet.cpp:250