mavtogpx.py 2.8 KB

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