From e3631aca91cd277e83363d4551961ccb795a4938 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 9 Feb 2022 09:12:02 +1100 Subject: [PATCH] autotest: print distance remaining while waiting for current wp --- Tools/autotest/common.py | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 663a013c87..1c4bb39f76 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -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