mavtcpsniff.py 2.9 KB

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