Go to the documentation of this file.00001
00002
00003 '''
00004 extract mavlink mission from log
00005 '''
00006
00007 import sys, time, os
00008
00009 from argparse import ArgumentParser
00010 parser = ArgumentParser(description=__doc__)
00011 parser.add_argument("--output", default='mission.txt', help="output file")
00012 parser.add_argument("logs", metavar="LOG", nargs="+")
00013
00014 args = parser.parse_args()
00015
00016 from pymavlink import mavutil, mavwp
00017
00018 parms = {}
00019
00020 def mavmission(logfile):
00021 '''extract mavlink mission'''
00022 mlog = mavutil.mavlink_connection(filename)
00023
00024 wp = mavwp.MAVWPLoader()
00025
00026 while True:
00027 m = mlog.recv_match(type=['MISSION_ITEM','CMD','WAYPOINT'])
00028 if m is None:
00029 break
00030 if m.get_type() == 'CMD':
00031 m = mavutil.mavlink.MAVLink_mission_item_message(0,
00032 0,
00033 m.CNum,
00034 mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
00035 m.CId,
00036 0, 1,
00037 m.Prm1, m.Prm2, m.Prm3, m.Prm4,
00038 m.Lat, m.Lng, m.Alt)
00039 if m.current >= 2:
00040 continue
00041
00042 while m.seq > wp.count():
00043 print("Adding dummy WP %u" % wp.count())
00044 wp.set(m, wp.count())
00045 wp.set(m, m.seq)
00046 wp.save(args.output)
00047 print("Saved %u waypoints to %s" % (wp.count(), args.output))
00048
00049
00050 total = 0.0
00051 for filename in args.logs:
00052 mavmission(filename)