autotest: wait for stats initialisation before rebooting
If the RTC time we reset parameters (STAT_RESET) is zero then we reset all parameters. In SITL we only set that time if we see a GPS due to the AP_RTC RTC_TYPES parameter default bitmask value of 1 So if you reboot SITL fast enough while STAT_RESET is zero you can see that STAT_BOOTCNT does not increase. Easily reproducible in SITL; start with -w and type reboot in several times before SITL sees the GPS come up and you can see STAT_BOOTCNT doesn't increase. Fix is to ensure STAT_RESET is non-zero before rebooting.
This commit is contained in:
parent
40bc087359
commit
e8f96efe72
@ -1570,6 +1570,16 @@ class AutoTest(ABC):
|
||||
|
||||
def reboot_sitl_mav(self, required_bootcount=None):
|
||||
"""Reboot SITL instance using mavlink and wait for it to reconnect."""
|
||||
# we must make sure that stats have been reset - otherwise
|
||||
# when we reboot we'll reset statistics again and lose our
|
||||
# STAT_BOOTCNT increment:
|
||||
tstart = time.time()
|
||||
while True:
|
||||
if time.time() - tstart > 30:
|
||||
raise NotAchievedException("STAT_RESET did not go non-zero")
|
||||
if self.get_parameter('STAT_RESET') != 0:
|
||||
break
|
||||
|
||||
old_bootcount = self.get_parameter('STAT_BOOTCNT')
|
||||
# ardupilot SITL may actually NAK the reboot; replace with
|
||||
# run_cmd when we don't do that.
|
||||
|
Loading…
Reference in New Issue
Block a user