4 connect as a client to two tcpip ports on localhost with mavlink packets. pass them both directions, and show packets in human-readable format on-screen. 7 * you have two SITL instances you want to connect to each other and see the comms. 8 * you have any tcpip based mavlink happening, and want something better than tcpdump 11 * you can use netcat/nc to do interesting redorection things with each end if you want to. 13 Copyright Sept 2012 David "Buzz" Bussenschutt 14 Released under GNU GPL version 3 or later 16 from __future__
import print_function
20 from pymavlink
import mavutil
23 from argparse
import ArgumentParser
24 parser = ArgumentParser(description=__doc__)
25 parser.add_argument(
"srcport", type=int)
26 parser.add_argument(
"dstport", type=int)
28 args = parser.parse_args()
30 msrc = mavutil.mavlink_connection(
'tcp:localhost:{}'.format(args.srcport), planner_format=
False,
34 mdst = mavutil.mavlink_connection(
'tcp:localhost:{}'.format(args.dstport), planner_format=
False,
56 msrc.logfile_raw = mdst
57 mdst.logfile_raw = msrc
61 l = msrc.recv_match();
64 if l.get_type() !=
'BAD_DATA':
65 l_timestamp = getattr(l,
'_timestamp',
None)
67 l_timestamp = l_last_timestamp
68 l_last_timestamp = l_timestamp
70 print(
"--> %s.%02u: %s\n" % (
71 time.strftime(
"%Y-%m-%d %H:%M:%S",
72 time.localtime(l._timestamp)),
73 int(l._timestamp*100.0)%100, l))
76 r = mdst.recv_match();
79 if r.get_type() !=
'BAD_DATA':
80 r_timestamp = getattr(r,
'_timestamp',
None)
82 r_timestamp = r_last_timestamp
83 r_last_timestamp = r_timestamp
85 print(
"<-- %s.%02u: %s\n" % (
86 time.strftime(
"%Y-%m-%d %H:%M:%S",
87 time.localtime(r._timestamp)),
88 int(r._timestamp*100.0)%100, r))