mavsummarize.py 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162
  1. #!/usr/bin/env python
  2. '''
  3. Summarize MAVLink logs. Useful for identifying which log is of interest in a large set.
  4. '''
  5. from __future__ import print_function
  6. from builtins import object
  7. import glob
  8. import time
  9. from argparse import ArgumentParser
  10. parser = ArgumentParser(description=__doc__)
  11. parser.add_argument("--no-timestamps", dest="notimestamps", action='store_true', help="Log doesn't have timestamps")
  12. parser.add_argument("--condition", default=None, help="condition for packets")
  13. parser.add_argument("--dialect", default="ardupilotmega", help="MAVLink dialect")
  14. parser.add_argument("logs", metavar="LOG", nargs="+")
  15. args = parser.parse_args()
  16. from pymavlink import mavutil
  17. from pymavlink.mavextra import distance_two
  18. class Totals(object):
  19. def __init__(self):
  20. self.time = 0
  21. self.distance = 0
  22. self.flights = 0
  23. def print_summary(self):
  24. print("===============================")
  25. print("Num Flights : %u" % self.flights)
  26. print("Total distance : {:0.2f}m".format(self.distance))
  27. print("Total time (mm:ss): {:3.0f}:{:02.0f}".format(self.time / 60, self.time % 60))
  28. totals = Totals()
  29. def PrintSummary(logfile):
  30. '''Calculate some interesting datapoints of the file'''
  31. # Open the log file
  32. mlog = mavutil.mavlink_connection(filename, notimestamps=args.notimestamps, dialect=args.dialect)
  33. autonomous_sections = 0 # How many different autonomous sections there are
  34. autonomous = False # Whether the vehicle is currently autonomous at this point in the logfile
  35. auto_time = 0.0 # The total time the vehicle was autonomous/guided (seconds)
  36. start_time = None # The datetime of the first received message (seconds since epoch)
  37. total_dist = 0.0 # The total ground distance travelled (meters)
  38. last_gps_msg = None # The first GPS message received
  39. first_gps_msg = None # The last GPS message received
  40. true_time = None # Track the first timestamp found that corresponds to a UNIX timestamp
  41. types = set(['HEARTBEAT', 'GPS_RAW_INT'])
  42. while True:
  43. m = mlog.recv_match(condition=args.condition, type=types)
  44. # If there's no match, it means we're done processing the log.
  45. if m is None:
  46. break
  47. # Ignore any failed messages
  48. if m.get_type() == 'BAD_DATA':
  49. continue
  50. # Keep track of the latest timestamp for various calculations
  51. timestamp = getattr(m, '_timestamp', 0.0)
  52. # Log the first message time
  53. if start_time is None:
  54. start_time = timestamp
  55. # Log the first timestamp found that is a true timestamp. We first try
  56. # to get the groundstation timestamp from the log directly. If that fails
  57. # we try to find a message that outputs a Unix time-since-epoch.
  58. if true_time is None:
  59. if not args.notimestamps and timestamp >= 1230768000:
  60. true_time = timestamp
  61. elif 'time_unix_usec' in m.__dict__ and m.time_unix_usec >= 1230768000:
  62. true_time = m.time_unix_usec * 1.0e-6
  63. elif 'time_usec' in m.__dict__ and m.time_usec >= 1230768000:
  64. true_time = m.time_usec * 1.0e-6
  65. # Track the vehicle's speed and status
  66. if m.get_type() == 'GPS_RAW_INT':
  67. # Ignore GPS messages without a proper fix
  68. if m.fix_type < 3 or m.lat == 0 or m.lon == 0:
  69. continue
  70. # Log the first GPS location found, being sure to skip GPS fixes
  71. # that are bad (at lat/lon of 0,0)
  72. if first_gps_msg is None:
  73. first_gps_msg = m
  74. # Track the distance travelled, being sure to skip GPS fixes
  75. # that are bad (at lat/lon of 0,0)
  76. if last_gps_msg is None or m.time_usec > last_gps_msg.time_usec or m.time_usec+30e6 < last_gps_msg.time_usec:
  77. if last_gps_msg is not None:
  78. total_dist += distance_two(last_gps_msg, m)
  79. # Save this GPS message to do simple distance calculations with
  80. last_gps_msg = m
  81. elif m.get_type() == 'HEARTBEAT':
  82. if m.type == mavutil.mavlink.MAV_TYPE_GCS:
  83. continue
  84. if (m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_GUIDED_ENABLED or
  85. m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_AUTO_ENABLED) and not autonomous:
  86. autonomous = True
  87. autonomous_sections += 1
  88. start_auto_time = timestamp
  89. elif (not m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_GUIDED_ENABLED and
  90. not m.base_mode & mavutil.mavlink.MAV_MODE_FLAG_AUTO_ENABLED) and autonomous:
  91. autonomous = False
  92. auto_time += timestamp - start_auto_time
  93. # If there were no messages processed, say so
  94. if start_time is None:
  95. print("ERROR: No messages found.")
  96. return
  97. # If the vehicle ends in autonomous mode, make sure we log the total time
  98. if autonomous:
  99. auto_time += timestamp - start_auto_time
  100. # Compute the total logtime, checking that timestamps are 2009 or newer for validity
  101. # (MAVLink didn't exist until 2009)
  102. if true_time:
  103. start_time_str = time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(true_time))
  104. print("Log started at about {}".format(start_time_str))
  105. else:
  106. print("Warning: No absolute timestamp found in datastream. No starting time can be provided for this log.")
  107. # Print location data
  108. if last_gps_msg is not None:
  109. first_gps_position = (first_gps_msg.lat / 1e7, first_gps_msg.lon / 1e7)
  110. last_gps_position = (last_gps_msg.lat / 1e7, last_gps_msg.lon / 1e7)
  111. print("Travelled from ({0[0]}, {0[1]}) to ({1[0]}, {1[1]})".format(first_gps_position, last_gps_position))
  112. print("Total distance : {:0.2f}m".format(total_dist))
  113. else:
  114. print("Warning: No GPS data found, can't give position summary.")
  115. # Print out the rest of the results.
  116. total_time = timestamp - start_time
  117. print("Total time (mm:ss): {:3.0f}:{:02.0f}".format(total_time / 60, total_time % 60))
  118. # The autonomous time should be good, as a steady HEARTBEAT is required for MAVLink operation
  119. print("Autonomous sections: {}".format(autonomous_sections))
  120. if autonomous_sections > 0:
  121. print("Autonomous time (mm:ss): {:3.0f}:{:02.0f}".format(auto_time / 60, auto_time % 60))
  122. totals.time += total_time
  123. totals.distance += total_dist
  124. totals.flights += 1
  125. for filename in args.logs:
  126. for f in glob.glob(filename):
  127. print("Processing log %s" % filename)
  128. PrintSummary(f)
  129. totals.print_summary()