mavtcpsniff.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
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.
5 
6 this is useful if
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
9 
10 hint:
11 * you can use netcat/nc to do interesting redorection things with each end if you want to.
12 
13 Copyright Sept 2012 David "Buzz" Bussenschutt
14 Released under GNU GPL version 3 or later
15 '''
16 from __future__ import print_function
17 
18 import time
19 
20 from pymavlink import mavutil
21 #from pymavlink import mavlinkv10 as mavlink
22 
23 from argparse import ArgumentParser
24 parser = ArgumentParser(description=__doc__)
25 parser.add_argument("srcport", type=int)
26 parser.add_argument("dstport", type=int)
27 
28 args = parser.parse_args()
29 
30 msrc = mavutil.mavlink_connection('tcp:localhost:{}'.format(args.srcport), planner_format=False,
31  notimestamps=True,
32  robust_parsing=True)
33 
34 mdst = mavutil.mavlink_connection('tcp:localhost:{}'.format(args.dstport), planner_format=False,
35  notimestamps=True,
36  robust_parsing=True)
37 
38 
39 # simple basic byte pass through, no logging or viewing of packets, or analysis etc
40 #while True:
41 # # L -> R
42 # m = msrc.recv();
43 # mdst.write(m);
44 # # R -> L
45 # m2 = mdst.recv();
46 # msrc.write(m2);
47 
48 
49 # similar to the above, but with human-readable display of packets on stdout.
50 # in this use case we abuse the self.logfile_raw() function to allow
51 # us to use the recv_match function ( whch is then calling recv_msg ) , to still get the raw data stream
52 # which we pass off to the other mavlink connection without any interference.
53 # because internally it will call logfile_raw.write() for us.
54 
55 # here we hook raw output of one to the raw input of the other, and vice versa:
56 msrc.logfile_raw = mdst
57 mdst.logfile_raw = msrc
58 
59 while True:
60  # L -> R
61  l = msrc.recv_match();
62  if l is not None:
63  l_last_timestamp = 0
64  if l.get_type() != 'BAD_DATA':
65  l_timestamp = getattr(l, '_timestamp', None)
66  if not l_timestamp:
67  l_timestamp = l_last_timestamp
68  l_last_timestamp = l_timestamp
69 
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))
74 
75  # R -> L
76  r = mdst.recv_match();
77  if r is not None:
78  r_last_timestamp = 0
79  if r.get_type() != 'BAD_DATA':
80  r_timestamp = getattr(r, '_timestamp', None)
81  if not r_timestamp:
82  r_timestamp = r_last_timestamp
83  r_last_timestamp = r_timestamp
84 
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))
89 
90 
91 


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Apr 7 2019 02:06:02