4 example program to extract GPS data from a mavlink log, and create a GPX 5 file, for loading into google earth 7 from __future__
import print_function
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()
18 from pymavlink
import mavutil
22 '''convert a mavlink log file to a GPX file''' 24 mlog = mavutil.mavlink_connection(infilename)
25 outf = open(outfilename, mode=
'w')
27 def process_packet(timestamp, lat, lon, alt, hdg, v):
28 t = time.localtime(timestamp)
29 outf.write(
'''<trkpt lat="%s" lon="%s"> 37 time.strftime(
"%Y-%m-%dT%H:%M:%SZ", t),
41 outf.write(
'''<?xml version="1.0" encoding="UTF-8"?> 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"> 53 outf.write(
'''</trkseg> 65 m = mlog.recv_match(type=[
'GPS_RAW',
'GPS_RAW_INT',
'GPS',
'GPS2'], condition=args.condition)
68 if m.get_type() ==
'GPS_RAW_INT':
74 timestamp = m._timestamp
76 elif m.get_type() ==
'GPS_RAW':
82 timestamp = m._timestamp
84 elif m.get_type() ==
'GPS' or m.get_type() ==
'GPS2':
90 timestamp = m._timestamp
95 if fix < 2
and not args.nofixcheck:
97 if lat == 0.0
or lon == 0.0:
99 process_packet(timestamp, lat, lon, alt, hdg, v)
102 print(
"Created %s with %u points" % (outfilename, count))
105 for infilename
in args.logs:
106 outfilename = infilename +
'.gpx'