mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
autotest: print distance remaining while waiting for current wp
This commit is contained in:
parent
13d5b00a22
commit
e3631aca91
@ -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…
Reference in New Issue
Block a user