mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
autotest: send all progress messages to autopilot
These will be logged into dataflash and into the telemetry log
This commit is contained in:
parent
d997ca8779
commit
0f5f040380
@ -830,12 +830,19 @@ class AutoTest(ABC):
|
|||||||
self.force_ahrs_type = int(self.force_ahrs_type)
|
self.force_ahrs_type = int(self.force_ahrs_type)
|
||||||
self.logs_dir = logs_dir
|
self.logs_dir = logs_dir
|
||||||
self.timesync_number = 137
|
self.timesync_number = 137
|
||||||
|
self.last_progress_sent_as_statustext = None
|
||||||
|
|
||||||
def progress(self, text):
|
def progress(self, text, send_statustext=True):
|
||||||
"""Display autotest progress text."""
|
"""Display autotest progress text."""
|
||||||
global __autotest__
|
global __autotest__
|
||||||
delta_time = time.time() - __autotest__.start_time
|
delta_time = time.time() - __autotest__.start_time
|
||||||
print("AT-%06.1f: %s" % (delta_time,text))
|
formatted_text = "AT-%06.1f: %s" % (delta_time,text)
|
||||||
|
print(formatted_text)
|
||||||
|
if (send_statustext and
|
||||||
|
self.mav is not None and
|
||||||
|
self.last_progress_sent_as_statustext != text):
|
||||||
|
self.send_statustext(formatted_text)
|
||||||
|
self.last_progress_sent_as_statustext = text
|
||||||
|
|
||||||
# following two functions swiped from autotest.py:
|
# following two functions swiped from autotest.py:
|
||||||
@staticmethod
|
@staticmethod
|
||||||
@ -1082,7 +1089,7 @@ class AutoTest(ABC):
|
|||||||
raise AutoTestTimeoutException("Did not detect reboot")
|
raise AutoTestTimeoutException("Did not detect reboot")
|
||||||
try:
|
try:
|
||||||
current_bootcount = self.get_parameter('STAT_BOOTCNT', timeout=1, attempts=3)
|
current_bootcount = self.get_parameter('STAT_BOOTCNT', timeout=1, attempts=3)
|
||||||
print("current=%s required=%u" % (str(current_bootcount), required_bootcount))
|
self.progress("current=%s required=%u" % (str(current_bootcount), required_bootcount))
|
||||||
if current_bootcount == required_bootcount:
|
if current_bootcount == required_bootcount:
|
||||||
break
|
break
|
||||||
except NotAchievedException:
|
except NotAchievedException:
|
||||||
@ -1654,7 +1661,7 @@ class AutoTest(ABC):
|
|||||||
rate = "instantly"
|
rate = "instantly"
|
||||||
else:
|
else:
|
||||||
rate = "%f/s" % (count/float(tdelta),)
|
rate = "%f/s" % (count/float(tdelta),)
|
||||||
self.progress("Drained %u bytes from mav (%s). These were unparsed." % (count, rate))
|
self.progress("Drained %u bytes from mav (%s). These were unparsed." % (count, rate), send_statustext=False)
|
||||||
if freshen_sim_time:
|
if freshen_sim_time:
|
||||||
self.get_sim_time()
|
self.get_sim_time()
|
||||||
|
|
||||||
@ -1673,7 +1680,7 @@ class AutoTest(ABC):
|
|||||||
else:
|
else:
|
||||||
rate = "%f/s" % (count/float(tdelta),)
|
rate = "%f/s" % (count/float(tdelta),)
|
||||||
|
|
||||||
self.progress("Drained %u messages from mav (%s)" % (count, rate))
|
self.progress("Drained %u messages from mav (%s)" % (count, rate), send_statustext=False)
|
||||||
|
|
||||||
def do_timesync_roundtrip(self):
|
def do_timesync_roundtrip(self):
|
||||||
self.progress("Doing timesync roundtrip")
|
self.progress("Doing timesync roundtrip")
|
||||||
@ -4167,7 +4174,6 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile)
|
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile)
|
||||||
|
|
||||||
prettyname = "%s (%s)" % (name, desc)
|
prettyname = "%s (%s)" % (name, desc)
|
||||||
self.send_statustext(prettyname)
|
|
||||||
self.start_test(prettyname)
|
self.start_test(prettyname)
|
||||||
self.set_current_test_name(name)
|
self.set_current_test_name(name)
|
||||||
old_contexts_length = len(self.contexts)
|
old_contexts_length = len(self.contexts)
|
||||||
|
@ -3554,12 +3554,12 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
continue
|
continue
|
||||||
t = m.get_type()
|
t = m.get_type()
|
||||||
if t == "POSITION_TARGET_GLOBAL_INT":
|
if t == "POSITION_TARGET_GLOBAL_INT":
|
||||||
self.progress("Target: (%s)" % str(m))
|
self.progress("Target: (%s)" % str(m), send_statustext=False)
|
||||||
elif t == "GLOBAL_POSITION_INT":
|
elif t == "GLOBAL_POSITION_INT":
|
||||||
self.progress("Position: (%s)" % str(m))
|
self.progress("Position: (%s)" % str(m), send_statustext=False)
|
||||||
delta = self.get_distance(mavutil.location(m.lat*1e-7, m.lon*1e-7, 0, 0),
|
delta = self.get_distance(mavutil.location(m.lat*1e-7, m.lon*1e-7, 0, 0),
|
||||||
loc)
|
loc)
|
||||||
self.progress("delta: %s" % str(delta))
|
self.progress("delta: %s" % str(delta), send_statustext=False)
|
||||||
if delta < max_delta:
|
if delta < max_delta:
|
||||||
self.progress("Reached destination")
|
self.progress("Reached destination")
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user