Browse Source

Tools: autotest: fail convertgpx if zip or gpsbabel fail

mission-4.1.18
Peter Barker 7 years ago
parent
commit
5aa8890e5b
  1. 13
      Tools/autotest/autotest.py

13
Tools/autotest/autotest.py

@ -137,14 +137,21 @@ def build_parameters():
def convert_gpx(): def convert_gpx():
"""Convert any tlog files to GPX and KML.""" """Convert any tlog files to GPX and KML."""
mavlog = glob.glob(buildlogs_path("*.tlog")) mavlog = glob.glob(buildlogs_path("*.tlog"))
passed = True
for m in mavlog: for m in mavlog:
util.run_cmd(util.reltopdir("modules/mavlink/pymavlink/tools/mavtogpx.py") + " --nofixcheck " + m) util.run_cmd(util.reltopdir("modules/mavlink/pymavlink/tools/mavtogpx.py") + " --nofixcheck " + m)
gpx = m + '.gpx' gpx = m + '.gpx'
kml = m + '.kml' kml = m + '.kml'
util.run_cmd('gpsbabel -i gpx -f %s -o kml,units=m,floating=1,extrude=1 -F %s' % (gpx, kml), checkfail=False) try:
util.run_cmd('zip %s.kmz %s.kml' % (m, m), checkfail=False) util.run_cmd('gpsbabel -i gpx -f %s -o kml,units=m,floating=1,extrude=1 -F %s' % (gpx, kml))
except CalledProcessError as e:
passed = False
try:
util.run_cmd('zip %s.kmz %s.kml' % (m, m))
except CalledProcessError as e:
passed = False
util.run_cmd("mavflightview.py --imagefile=%s.png %s" % (m, m)) util.run_cmd("mavflightview.py --imagefile=%s.png %s" % (m, m))
return True return passed
def test_prerequisites(): def test_prerequisites():

Loading…
Cancel
Save