mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
autotest: prompt ArduPilot for SYSTEM_TIME message during reboot
This helps us actually execute the timeouts appropriately and thus re-fetch the STAT_BOOTCNT parameter we use for detecting the reboot Eliminates annoying pauses during testing.
This commit is contained in:
parent
8e6d144d72
commit
4d19ff6b26
@ -1529,15 +1529,27 @@ class AutoTest(ABC):
|
||||
if required_bootcount is None:
|
||||
required_bootcount = old_bootcount + 1
|
||||
while True:
|
||||
# get_parameter calls get_sim_time.... streamrates may
|
||||
# be zero so we need to prompt for one of these...
|
||||
self.send_cmd(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE,
|
||||
mavutil.mavlink.MAVLINK_MSG_ID_SYSTEM_TIME,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0)
|
||||
if time.time() - tstart > timeout:
|
||||
raise AutoTestTimeoutException("Did not detect reboot")
|
||||
try:
|
||||
current_bootcount = self.get_parameter('STAT_BOOTCNT', timeout=1, attempts=3)
|
||||
current_bootcount = self.get_parameter('STAT_BOOTCNT', timeout=1, attempts=1)
|
||||
self.progress("current=%s required=%u" % (str(current_bootcount), required_bootcount))
|
||||
if current_bootcount == required_bootcount:
|
||||
break
|
||||
except NotAchievedException:
|
||||
pass
|
||||
except AutoTestTimeoutException:
|
||||
pass
|
||||
|
||||
# empty mav to avoid getting old timestamps:
|
||||
self.drain_mav()
|
||||
@ -3534,7 +3546,7 @@ class AutoTest(ABC):
|
||||
# we MUST parse here or collections fail where we need
|
||||
# them to work!
|
||||
self.drain_mav(quiet=True)
|
||||
tstart = self.get_sim_time()
|
||||
tstart = self.get_sim_time(timeout=timeout)
|
||||
encname = name
|
||||
if sys.version_info.major >= 3 and type(encname) != bytes:
|
||||
encname = bytes(encname, 'ascii')
|
||||
|
Loading…
Reference in New Issue
Block a user