mavmission.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 extract mavlink mission from log
5 '''
6 from __future__ import print_function
7 
8 from argparse import ArgumentParser
9 parser = ArgumentParser(description=__doc__)
10 parser.add_argument("--output", default='mission.txt', help="output file")
11 parser.add_argument("logs", metavar="LOG", nargs="+")
12 
13 args = parser.parse_args()
14 
15 from pymavlink import mavutil, mavwp
16 
17 parms = {}
18 
19 def mavmission(logfile):
20  '''extract mavlink mission'''
21  mlog = mavutil.mavlink_connection(filename)
22 
23  wp = mavwp.MAVWPLoader()
24 
25  while True:
26  m = mlog.recv_match(type=['MISSION_ITEM','CMD','WAYPOINT'])
27  if m is None:
28  break
29  if m.get_type() == 'CMD':
30  m = mavutil.mavlink.MAVLink_mission_item_message(0,
31  0,
32  m.CNum,
33  mavutil.mavlink.MAV_FRAME_GLOBAL_RELATIVE_ALT,
34  m.CId,
35  0, 1,
36  m.Prm1, m.Prm2, m.Prm3, m.Prm4,
37  m.Lat, m.Lng, m.Alt)
38  if m.current >= 2:
39  continue
40 
41  while m.seq > wp.count():
42  print("Adding dummy WP %u" % wp.count())
43  wp.set(m, wp.count())
44  wp.set(m, m.seq)
45  wp.save(args.output)
46  print("Saved %u waypoints to %s" % (wp.count(), args.output))
47 
48 
49 total = 0.0
50 for filename in args.logs:
51  mavmission(filename)


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