mavtogpx.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4 example program to extract GPS data from a mavlink log, and create a GPX
5 file, for loading into google earth
6 '''
7 from __future__ import print_function
8 
9 import time
10 
11 from argparse import ArgumentParser
12 parser = ArgumentParser(description=__doc__)
13 parser.add_argument("--condition", default=None, help="select packets by a condition")
14 parser.add_argument("--nofixcheck", default=False, action='store_true', help="don't check for GPS fix")
15 parser.add_argument("logs", metavar="LOG", nargs="+")
16 args = parser.parse_args()
17 
18 from pymavlink import mavutil
19 
20 
21 def mav_to_gpx(infilename, outfilename):
22  '''convert a mavlink log file to a GPX file'''
23 
24  mlog = mavutil.mavlink_connection(infilename)
25  outf = open(outfilename, mode='w')
26 
27  def process_packet(timestamp, lat, lon, alt, hdg, v):
28  t = time.localtime(timestamp)
29  outf.write('''<trkpt lat="%s" lon="%s">
30  <ele>%s</ele>
31  <time>%s</time>
32  <course>%s</course>
33  <speed>%s</speed>
34  <fix>3d</fix>
35 </trkpt>
36 ''' % (lat, lon, alt,
37  time.strftime("%Y-%m-%dT%H:%M:%SZ", t),
38  hdg, v))
39 
40  def add_header():
41  outf.write('''<?xml version="1.0" encoding="UTF-8"?>
42 <gpx
43  version="1.0"
44  creator="pymavlink"
45  xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
46  xmlns="http://www.topografix.com/GPX/1/0"
47  xsi:schemaLocation="http://www.topografix.com/GPX/1/0 http://www.topografix.com/GPX/1/0/gpx.xsd">
48 <trk>
49 <trkseg>
50 ''')
51 
52  def add_footer():
53  outf.write('''</trkseg>
54 </trk>
55 </gpx>
56 ''')
57 
58  add_header()
59 
60  count=0
61  lat=0
62  lon=0
63  fix=0
64  while True:
65  m = mlog.recv_match(type=['GPS_RAW', 'GPS_RAW_INT', 'GPS', 'GPS2'], condition=args.condition)
66  if m is None:
67  break
68  if m.get_type() == 'GPS_RAW_INT':
69  lat = m.lat/1.0e7
70  lon = m.lon/1.0e7
71  alt = m.alt/1.0e3
72  v = m.vel/100.0
73  hdg = m.cog/100.0
74  timestamp = m._timestamp
75  fix = m.fix_type
76  elif m.get_type() == 'GPS_RAW':
77  lat = m.lat
78  lon = m.lon
79  alt = m.alt
80  v = m.v
81  hdg = m.hdg
82  timestamp = m._timestamp
83  fix = m.fix_type
84  elif m.get_type() == 'GPS' or m.get_type() == 'GPS2':
85  lat = m.Lat
86  lon = m.Lng
87  alt = m.Alt
88  v = m.Spd
89  hdg = m.GCrs
90  timestamp = m._timestamp
91  fix = m.Status
92  else:
93  pass
94 
95  if fix < 2 and not args.nofixcheck:
96  continue
97  if lat == 0.0 or lon == 0.0:
98  continue
99  process_packet(timestamp, lat, lon, alt, hdg, v)
100  count += 1
101  add_footer()
102  print("Created %s with %u points" % (outfilename, count))
103 
104 
105 for infilename in args.logs:
106  outfilename = infilename + '.gpx'
107  mav_to_gpx(infilename, outfilename)


mavlink
Author(s): Lorenz Meier
autogenerated on Sun Jul 7 2019 03:22:07