Go to the documentation of this file.00001
00002
00003 '''
00004 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.
00005
00006 this is useful if
00007 * you have two SITL instances you want to connect to each other and see the comms.
00008 * you have any tcpip based mavlink happening, and want something better than tcpdump
00009
00010 hint:
00011 * you can use netcat/nc to do interesting redorection things with each end if you want to.
00012
00013 Copyright Sept 2012 David "Buzz" Bussenschutt
00014 Released under GNU GPL version 3 or later
00015 '''
00016
00017 import sys, time, os, struct
00018
00019 from pymavlink import mavutil
00020
00021
00022 from argparse import ArgumentParser
00023 parser = ArgumentParser(description=__doc__)
00024 parser.add_argument("srcport", type=int)
00025 parser.add_argument("dstport", type=int)
00026
00027 args = parser.parse_args()
00028
00029 msrc = mavutil.mavlink_connection('tcp:localhost:{}'.format(args.srcport), planner_format=False,
00030 notimestamps=True,
00031 robust_parsing=True)
00032
00033 mdst = mavutil.mavlink_connection('tcp:localhost:{}'.format(args.dstport), planner_format=False,
00034 notimestamps=True,
00035 robust_parsing=True)
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055 msrc.logfile_raw = mdst
00056 mdst.logfile_raw = msrc
00057
00058 while True:
00059
00060 l = msrc.recv_match();
00061 if l is not None:
00062 l_last_timestamp = 0
00063 if l.get_type() != 'BAD_DATA':
00064 l_timestamp = getattr(l, '_timestamp', None)
00065 if not l_timestamp:
00066 l_timestamp = l_last_timestamp
00067 l_last_timestamp = l_timestamp
00068
00069 print("--> %s.%02u: %s\n" % (
00070 time.strftime("%Y-%m-%d %H:%M:%S",
00071 time.localtime(l._timestamp)),
00072 int(l._timestamp*100.0)%100, l))
00073
00074
00075 r = mdst.recv_match();
00076 if r is not None:
00077 r_last_timestamp = 0
00078 if r.get_type() != 'BAD_DATA':
00079 r_timestamp = getattr(r, '_timestamp', None)
00080 if not r_timestamp:
00081 r_timestamp = r_last_timestamp
00082 r_last_timestamp = r_timestamp
00083
00084 print("<-- %s.%02u: %s\n" % (
00085 time.strftime("%Y-%m-%d %H:%M:%S",
00086 time.localtime(r._timestamp)),
00087 int(r._timestamp*100.0)%100, r))
00088
00089
00090