Browse Source

autotest: print distance remaining while waiting for current wp

gps-1.3.1
Peter Barker 3 years ago committed by Peter Barker
parent
commit
e3631aca91
  1. 7
      Tools/autotest/common.py

7
Tools/autotest/common.py

@ -5906,7 +5906,12 @@ class AutoTest(ABC): @@ -5906,7 +5906,12 @@ class AutoTest(ABC):
if self.get_sim_time() - tstart > timeout:
raise AutoTestTimeoutException("Did not get wanted current waypoint")
seq = self.mav.waypoint_current()
self.progress("Waiting for wp=%u current=%u" % (wpnum, seq))
wp_dist = None
try:
wp_dist = self.mav.messages['NAV_CONTROLLER_OUTPUT'].wp_dist
except (KeyError, AttributeError):
pass
self.progress("Waiting for wp=%u current=%u dist=%sm" % (wpnum, seq, wp_dist))
if seq == wpnum:
break

Loading…
Cancel
Save