mavtables  0.2.1
MAVLink router and firewall.
integration_tests/run_tests.sh
Go to the documentation of this file.
1 #!/bin/bash
2 
3 
4 FAIL=0
5 
6 
7 function dir() {
8  DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
9  echo "$DIR"
10 }
11 
12 
13 source "$(dir)/../ansi_codes.sh"
14 
15 
16 function run_test() {
17  PAD=$(printf '%0.1s' "."{1..80})
18  printf "${_BOLD}%s${ANSI_RESET}" "$1 "
19  $2
20  DIFF=$(diff "$(dir)/$4" "$(dir)/$3")
21  if [ "$DIFF" != "" ]; then
22  printf "%*.*s" 0 $((67 - ${#1})) "$PAD"
23  printf " ${_BOLD}${_RED}%s${ANSI_RESET}\n" "[FAILED]"
24  echo "$DIFF"
25  FAIL=1
26  else
27  printf "%*.*s" 0 $((66 - ${#1})) "$PAD"
28  printf " ${_BOLD}${_GREEN}%s${ANSI_RESET}\n" "[SUCCESS]"
29  fi
30 }
31 
32 
33 function shutdown_background() {
34  array=($(jobs -p))
35  for ((i = ${#array[@]} - 1; i >= 0; i--)); do
36  kill -SIGINT ${array[i]} 2>/dev/null
37  sleep 2
38  done
39 }
40 
41 
42 function do_nothing() {
43  echo "do nothing" >/dev/null
44 }
45 
46 
47 function test_ast_printing() {
48  "$(dir)/../../build/mavtables" --ast --conf "$(dir)/../mavtables.conf" \
49  | tail -n +2 > "$(dir)/mavtables.log"
50 }
51 
52 
53 function test_complex_ast_printing() {
54  "$(dir)/../../build/mavtables" --ast \
55  --conf "$(dir)/complex_config.conf" \
56  | tail -n +2 > "$(dir)/complex_config.log"
57 }
58 
59 
60 function test_all_v1_packets_udp() {
61  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
62  sleep 2
63  "$(dir)/../../build/mavtables" --conf "$(dir)/all_1serial.conf" &
64  "$(dir)/logger.py" 12 26 --udp 127.0.0.1:14500 \
65  > "$(dir)/all_v1_packets_udp_to_udp.log" &
66  "$(dir)/logger.py" 29 39 --serial ./ttyS1 \
67  > "$(dir)/all_v1_packets_udp_to_serial.log" &
68  sleep 2
69  "$(dir)/packet_scripter.py" 192 168 "$(dir)/all_v1_packets.pks" \
70  --udp 127.0.0.1:14500 --mavlink1
71  sleep 2
72  shutdown_background
73 }
74 
75 
76 function test_all_v2_packets_udp() {
77  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
78  sleep 2
79  "$(dir)/../../build/mavtables" --conf "$(dir)/all_1serial.conf" &
80  "$(dir)/logger.py" 12 26 --udp 127.0.0.1:14500 \
81  > "$(dir)/all_v2_packets_udp_to_udp.log" &
82  "$(dir)/logger.py" 29 39 --serial ./ttyS1 \
83  > "$(dir)/all_v2_packets_udp_to_serial.log" &
84  sleep 2
85  "$(dir)/packet_scripter.py" 192 168 "$(dir)/all_v2_packets.pks" \
86  --udp 127.0.0.1:14500
87  sleep 2
88  shutdown_background
89 }
90 
91 
92 function test_all_v1_packets_serial() {
93  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
94  socat pty,link=./ttyS2,raw,echo=0 pty,link=./ttyS3,raw,echo=0 &
95  sleep 2
96  "$(dir)/../../build/mavtables" --conf "$(dir)/all_2serial.conf" &
97  "$(dir)/logger.py" 12 26 --udp 127.0.0.1:14500 \
98  > "$(dir)/all_v1_packets_serial_to_udp.log" &
99  "$(dir)/logger.py" 29 39 --serial ./ttyS1 \
100  > "$(dir)/all_v1_packets_serial_to_serial.log" &
101  sleep 2
102  "$(dir)/packet_scripter.py" 192 168 "$(dir)/all_v1_packets.pks" \
103  --serial ./ttyS3 --mavlink1
104  sleep 2
105  shutdown_background
106 }
107 
108 
109 function test_all_v2_packets_serial() {
110  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
111  socat pty,link=./ttyS2,raw,echo=0 pty,link=./ttyS3,raw,echo=0 &
112  sleep 2
113  "$(dir)/../../build/mavtables" --conf "$(dir)/all_2serial.conf" &
114  "$(dir)/logger.py" 12 26 --udp 127.0.0.1:14500 \
115  > "$(dir)/all_v2_packets_serial_to_udp.log" &
116  "$(dir)/logger.py" 29 39 --serial ./ttyS1 \
117  > "$(dir)/all_v2_packets_serial_to_serial.log" &
118  sleep 2
119  "$(dir)/packet_scripter.py" 192 168 "$(dir)/all_v2_packets.pks" \
120  --serial ./ttyS3
121  sleep 2
122  shutdown_background
123 }
124 
125 
126 function test_multiple_senders_v1_packets() {
127  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
128  socat pty,link=./ttyS2,raw,echo=0 pty,link=./ttyS3,raw,echo=0 &
129  sleep 2
130  "$(dir)/../../build/mavtables" --conf "$(dir)/all_2serial.conf" &
131  "$(dir)/logger.py" 12 26 --udp 127.0.0.1:14500 --verbose \
132  | sort --version-sort \
133  > "$(dir)/multiple_senders_v1_packets_to_udp.log" &
134  "$(dir)/logger.py" 10 20 --serial ./ttyS1 --verbose \
135  | sort --version-sort \
136  > "$(dir)/multiple_senders_v1_packets_to_serial.log" &
137  sleep 2
138  "$(dir)/packet_scripter.py" 192 168 "$(dir)/all_v1_packets.pks" \
139  --udp 127.0.0.1:14500 --mavlink1 &
140  "$(dir)/packet_scripter.py" 172 128 "$(dir)/all_v1_packets.pks" \
141  --udp 127.0.0.1:14500 --mavlink1 &
142  "$(dir)/packet_scripter.py" 127 1 "$(dir)/all_v1_packets.pks" \
143  --serial ./ttyS3 --mavlink1
144  sleep 2
145  shutdown_background
146 }
147 
148 
149 function test_multiple_senders_v2_packets() {
150  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
151  socat pty,link=./ttyS2,raw,echo=0 pty,link=./ttyS3,raw,echo=0 &
152  sleep 2
153  "$(dir)/../../build/mavtables" --conf "$(dir)/all_2serial.conf" &
154  "$(dir)/logger.py" 12 26 --udp 127.0.0.1:14500 --verbose \
155  | sort --version-sort \
156  > "$(dir)/multiple_senders_v2_packets_to_udp.log" &
157  "$(dir)/logger.py" 10 20 --serial ./ttyS1 --verbose \
158  | sort --version-sort \
159  > "$(dir)/multiple_senders_v2_packets_to_serial.log" &
160  sleep 2
161  "$(dir)/packet_scripter.py" 192 168 "$(dir)/all_v2_packets.pks" \
162  --udp 127.0.0.1:14500 &
163  "$(dir)/packet_scripter.py" 172 128 "$(dir)/all_v2_packets.pks" \
164  --udp 127.0.0.1:14500 &
165  "$(dir)/packet_scripter.py" 127 1 "$(dir)/all_v2_packets.pks" \
166  --serial ./ttyS3
167  sleep 2
168  shutdown_background
169 }
170 
171 
172 function test_routing_v1_packets() {
173  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
174  sleep 2
175  "$(dir)/../../build/mavtables" --conf "$(dir)/routing.conf" &
176  "$(dir)/logger.py" 127 1 --udp 127.0.0.1:14500 \
177  > "$(dir)/routing_v1_packets_127.1.log" &
178  "$(dir)/logger.py" 192 168 --udp 127.0.0.1:14500 \
179  > "$(dir)/routing_v1_packets_192.168.log" &
180  "$(dir)/logger.py" 172 128 --serial ./ttyS1 \
181  > "$(dir)/routing_v1_packets_172.128.log" &
182  sleep 2
183  "$(dir)/packet_scripter.py" 10 10 "$(dir)/routing.pks" \
184  --udp 127.0.0.1:14500 --mavlink1
185  sleep 2
186  shutdown_background
187 }
188 
189 
190 function test_routing_v2_packets() {
191  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
192  sleep 2
193  "$(dir)/../../build/mavtables" --conf "$(dir)/routing.conf" &
194  "$(dir)/logger.py" 127 1 --udp 127.0.0.1:14500 \
195  > "$(dir)/routing_v2_packets_127.1.log" &
196  "$(dir)/logger.py" 192 168 --udp 127.0.0.1:14500 \
197  > "$(dir)/routing_v2_packets_192.168.log" &
198  "$(dir)/logger.py" 172 128 --serial ./ttyS1 \
199  > "$(dir)/routing_v2_packets_172.128.log" &
200  sleep 2
201  "$(dir)/packet_scripter.py" 10 10 "$(dir)/routing.pks" \
202  --udp 127.0.0.1:14500
203  sleep 2
204  shutdown_background
205 }
206 
207 
208 function test_priority() {
209  perl -e 'for$i(1..50){print "ENCAPSULATED_DATA\n"}' \
210  > "$(dir)/priority.tmp"
211  perl -e 'for$i(1..100){print "ATTITUDE\n"}' \
212  >> "$(dir)/priority.tmp"
213  perl -e 'for$i(1..100){print "GLOBAL_POSITION_INT\n"}' \
214  >> "$(dir)/priority.tmp"
215  perl -e 'for$i(1..50){print "ENCAPSULATED_DATA\n"}' \
216  >> "$(dir)/priority.tmp"
217  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
218  sleep 2
219  "$(dir)/../../build/mavtables" --conf "$(dir)/priority.conf" &
220  "$(dir)/logger.py" 192 168 --udp 127.0.0.1:14500 > "$(dir)/priority.log" &
221  sleep 2
222  "$(dir)/packet_scripter.py" 10 10 "$(dir)/priority.tmp" --serial ./ttyS1
223  sleep 2
224  perl -e 'for$i(1..100){print "ENCAPSULATED_DATA\n"}' \
225  > "$(dir)/priority.tmp"
226  perl -e 'for$i(1..100){print "GLOBAL_POSITION_INT\n"}' \
227  >> "$(dir)/priority.tmp"
228  perl -e 'for$i(1..100){print "ATTITUDE\n"}' \
229  >> "$(dir)/priority.tmp"
230  shutdown_background
231 }
232 
233 
234 function test_preload_addresses() {
235  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
236  sleep 2
237  "$(dir)/../../build/mavtables" --conf "$(dir)/preload.conf" &
238  "$(dir)/logger.py" 10 10 --noheartbeat --serial ./ttyS1 \
239  > "$(dir)/preload.log" &
240  sleep 2
241  "$(dir)/packet_scripter.py" 123 123 "$(dir)/routing.pks" \
242  --udp 127.0.0.1:14500
243  sleep 2
244  shutdown_background
245 }
246 
247 
248 function test_component_broadcast_fallback() {
249  perl -e 'for$i(0..255){print "MISSION_REQUEST_LIST to 1.$i\n"}' \
250  > "$(dir)/component_broadcast_fallback.tmp"
251  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
252  sleep 2
253  "$(dir)/../../build/mavtables" \
254  --conf "$(dir)/component_broadcast_fallback.conf" &
255  "$(dir)/logger.py" 1 1 --verbose --serial ./ttyS1 \
256  > "$(dir)/component_broadcast_fallback.log" &
257  sleep 2
258  "$(dir)/packet_scripter.py" 10 10 \
259  "$(dir)/component_broadcast_fallback.tmp" \
260  --udp 127.0.0.1:14500
261  perl -e \
262  'for$i(128..255){print "MISSION_REQUEST_LIST from 10.10 to 1.$i\n"}' \
263  > "$(dir)/component_broadcast_fallback.tmp"
264  sleep 2
265  shutdown_background
266 }
267 
268 
269 function test_large_packets() {
270  perl -e 'for$i(1..5000){print "ENCAPSULATED_DATA\n"}' \
271  > "$(dir)/large_packets.tmp"
272  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
273  socat pty,link=./ttyS2,raw,echo=0 pty,link=./ttyS3,raw,echo=0 &
274  sleep 2
275  "$(dir)/../../build/mavtables" --conf "$(dir)/all_2serial.conf" &
276  "$(dir)/logger.py" 12 26 --udp 127.0.0.1:14500 \
277  > "$(dir)/large_packets_to_udp.log" &
278  "$(dir)/logger.py" 10 20 --serial ./ttyS1 \
279  > "$(dir)/large_packets_to_serial.log" &
280  sleep 2
281  "$(dir)/packet_scripter.py" 192 168 "$(dir)/large_packets.tmp" \
282  --udp 127.0.0.1:14500 &
283  "$(dir)/packet_scripter.py" 172 128 "$(dir)/large_packets.tmp" \
284  --serial ./ttyS3
285  sleep 60
286  perl -e 'for$i(1..5000){print "ENCAPSULATED_DATA\n"}' \
287  >> "$(dir)/large_packets.tmp"
288  shutdown_background
289 }
290 
291 
292 function test_logging_level1() {
293  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
294  sleep 1
295  "$(dir)/../../build/mavtables" --loglevel 1 --conf "$(dir)/routing.conf" \
296  > "$(dir)/logging_level1.log" &
297  sleep 1
298  "$(dir)/logger.py" 127 1 --udp 127.0.0.1:14500 > /dev/null &
299  sleep 1
300  "$(dir)/logger.py" 192 168 --udp 127.0.0.1:14500 > /dev/null &
301  sleep 1
302  "$(dir)/logger.py" 172 128 --serial ./ttyS1 > /dev/null &
303  sleep 1
304  "$(dir)/packet_scripter.py" 10 10 "$(dir)/routing.pks" \
305  --udp 127.0.0.1:14500
306  sleep 1
307  sed -i 's/^.....................//' "$(dir)/logging_level1.log"
308  sed -i 's/:[0-9]*//g' "$(dir)/logging_level1.log"
309  shutdown_background
310 }
311 
312 
313 function test_logging_level2() {
314  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
315  sleep 1
316  "$(dir)/../../build/mavtables" --loglevel 2 --conf "$(dir)/routing.conf" \
317  > "$(dir)/logging_level2.log" &
318  sleep 1
319  "$(dir)/logger.py" 127 1 --udp 127.0.0.1:14500 > /dev/null &
320  sleep 1
321  "$(dir)/logger.py" 192 168 --udp 127.0.0.1:14500 > /dev/null &
322  sleep 1
323  "$(dir)/logger.py" 172 128 --serial ./ttyS1 > /dev/null &
324  sleep 1
325  "$(dir)/packet_scripter.py" 10 10 "$(dir)/routing.pks" \
326  --udp 127.0.0.1:14500
327  sleep 1
328  sed -i 's/^.....................//' "$(dir)/logging_level2.log"
329  sed -i 's/:[0-9]*//g' "$(dir)/logging_level2.log"
330  shutdown_background
331 }
332 
333 
334 function test_logging_level3() {
335  socat pty,link=./ttyS0,raw,echo=0 pty,link=./ttyS1,raw,echo=0 &
336  sleep 1
337  "$(dir)/../../build/mavtables" --loglevel 3 --conf "$(dir)/routing.conf" \
338  > "$(dir)/logging_level3.log" &
339  sleep 1
340  "$(dir)/logger.py" 127 1 --udp 127.0.0.1:14500 > /dev/null &
341  sleep 1
342  "$(dir)/logger.py" 192 168 --udp 127.0.0.1:14500 > /dev/null &
343  sleep 1
344  "$(dir)/logger.py" 172 128 --serial ./ttyS1 > /dev/null &
345  sleep 1
346  "$(dir)/packet_scripter.py" 10 10 "$(dir)/routing.pks" \
347  --udp 127.0.0.1:14500
348  sleep 1
349  sed -i 's/^.....................//' "$(dir)/logging_level3.log"
350  sed -i 's/:[0-9]*//g' "$(dir)/logging_level3.log"
351  shutdown_background
352 }
353 
354 
355 echo -en "${_BOLD}${_BLUE}*---------------------------------------"
356 echo -en "--------------------------------------*\n"
357 echo -en "${_BOLD}${_BLUE}| "
358 echo -en "Integration Tests"
359 echo -en " |\n"
360 echo -en "${_BOLD}${_BLUE}*---------------------------------------"
361 echo -en "--------------------------------------*\n"
362 echo -en "${ANSI_RESET}"
363 
364 
365 rm "$(dir)"/*.log 2>/dev/null
366 
367 
368 case "$OSTYPE" in
369  solaris*)
370  ;;
371  darwin*)
372  echo -en "${_BOLD}${_ITALICS}${_RED}Integration testing is not currently "
373  echo -en "supported on Mac OS X.${ANSI_RESET}\n\n"
374  exit 0
375  ;;
376  linux*)
377  ;;
378  bsd*)
379  ;;
380  *)
381  echo "unknown operating system: $OSTYPE"
382  exit 1
383  ;;
384 esac
385 
386 
387 function check_fail() {
388  if [ "$?" -ne "0" ]; then
389  FAIL=1
390  fi
391 }
392 
393 
394 run_test "Abstract Syntax Tree printing with --ast flag" \
395  test_ast_printing \
396  mavtables.cmp \
397  mavtables.log
398 run_test "Complex Abstract Syntax Tree printing with --ast flag" \
399  test_complex_ast_printing \
400  complex_config.cmp \
401  complex_config.log
402 
403 
404 run_test "All MAVLink v1.0 packets from UDP to UDP" \
405  test_all_v1_packets_udp \
406  all_v1_packets.pks \
407  all_v1_packets_udp_to_udp.log
408 run_test "All MAVLink v1.0 packets from UDP to serial port" \
409  do_nothing \
410  all_v1_packets.pks \
411  all_v1_packets_udp_to_serial.log
412 run_test "All MAVLink v2.0 packets from UDP to UDP" \
413  test_all_v2_packets_udp \
414  all_v2_packets.pks \
415  all_v2_packets_udp_to_udp.log
416 run_test "All MAVLink v2.0 packets from UDP to serial port" \
417  do_nothing \
418  all_v2_packets.pks \
419  all_v2_packets_udp_to_serial.log
420 
421 
422 run_test "All MAVLink v1.0 packets from serial port to UDP" \
423  test_all_v1_packets_serial \
424  all_v1_packets.pks \
425  all_v1_packets_serial_to_udp.log
426 run_test "All MAVLink v1.0 packets from serial port to serial port" \
427  do_nothing \
428  all_v1_packets.pks \
429  all_v1_packets_serial_to_serial.log
430 run_test "All MAVLink v2.0 packets from serial port to UDP" \
431  test_all_v2_packets_serial \
432  all_v2_packets.pks \
433  all_v2_packets_serial_to_udp.log
434 run_test "All MAVLink v2.0 packets from serial port to serial port" \
435  do_nothing \
436  all_v2_packets.pks \
437  all_v2_packets_serial_to_serial.log
438 
439 
440 run_test "Multiple senders with MAVLink v1.0 packets to UDP" \
441  test_multiple_senders_v1_packets \
442  multiple_senders_v1_packets.cmp \
443  multiple_senders_v1_packets_to_udp.log
444 run_test "Multiple senders with MAVLink v1.0 packets to serial port" \
445  do_nothing \
446  multiple_senders_v1_packets.cmp \
447  multiple_senders_v1_packets_to_serial.log
448 run_test "Multiple senders with MAVLink v2.0 packets to UDP" \
449  test_multiple_senders_v2_packets \
450  multiple_senders_v2_packets.cmp \
451  multiple_senders_v2_packets_to_udp.log
452 run_test "Multiple senders with MAVLink v2.0 packets to serial port" \
453  do_nothing \
454  multiple_senders_v2_packets.cmp \
455  multiple_senders_v2_packets_to_serial.log
456 
457 
458 run_test "Routing MAVLink v1.0 packets (part 1 - 127.1)" \
459  test_routing_v1_packets routing_127.1.cmp routing_v1_packets_127.1.log
460 run_test "Routing MAVLink v1.0 packets (part 2 - 192.168)" \
461  do_nothing routing_192.168.cmp routing_v1_packets_192.168.log
462 run_test "Routing MAVLink v1.0 packets (part 3 - 172.128)" \
463  do_nothing routing_172.128.cmp routing_v1_packets_172.128.log
464 
465 
466 run_test "Routing MAVLink v2.0 packets (part 1 - 127.1)" \
467  test_routing_v2_packets routing_127.1.cmp routing_v2_packets_127.1.log
468 run_test "Routing MAVLink v2.0 packets (part 2 - 192.168)" \
469  do_nothing routing_192.168.cmp routing_v2_packets_192.168.log
470 run_test "Routing MAVLink v2.0 packets (part 3 - 172.128)" \
471  do_nothing routing_172.128.cmp routing_v2_packets_172.128.log
472 
473 
474 run_test "High priority packets are transmitted first" \
475  test_priority priority.tmp priority.log
476 
477 
478 run_test "Serial ports can be preloaded with MAVLink addresses" \
479  test_preload_addresses preload.cmp preload.log
480 
481 
482 run_test "Component broadcast fallback and MAVLink subnets" \
483  test_component_broadcast_fallback \
484  component_broadcast_fallback.tmp \
485  component_broadcast_fallback.log
486 
487 
488 run_test "Many large packets with multiple senders to UDP" \
489  test_large_packets large_packets.tmp large_packets_to_udp.log
490 run_test "Many large packets with multiple senders to serial port" \
491  do_nothing large_packets.tmp large_packets_to_serial.log
492 
493 
494 run_test "Logging level 1" \
495  test_logging_level1 logging_level1.cmp logging_level1.log
496 run_test "Logging level 2" \
497  test_logging_level2 logging_level2.cmp logging_level2.log
498 run_test "Logging level 3" \
499  test_logging_level3 logging_level3.cmp logging_level3.log
500 
501 
502 if [ "$FAIL" -ne "0" ]; then
503  echo -en "\n"
504  exit $FAIL
505 fi