From 217338955d4cbbf2ffdc0af3e3762d61fb148ac0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 24 Aug 2022 11:12:32 +1000 Subject: [PATCH] autotest: wait for logging to be good in replay GPS test I think it's possible for the reboot to be coplete but the log not yet open as it's done in the update call --- Tools/autotest/arducopter.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 2a4fb015b5..514964bc21 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -7480,6 +7480,8 @@ class AutoTestCopter(AutoTest): }) self.reboot_sitl() + self.wait_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_LOGGING, True, True, True) + current_log_filepath = self.current_onboard_log_filepath() self.progress("Current log path: %s" % str(current_log_filepath)) @@ -7692,7 +7694,9 @@ class AutoTestCopter(AutoTest): self.context_push() current_log_filepath = bit() - self.progress("Running replay on (%s)" % current_log_filepath) + self.progress("Running replay on (%s) (%u bytes)" % ( + (current_log_filepath, os.path.getsize(current_log_filepath)) + )) util.run_cmd( ['build/sitl/tool/Replay', current_log_filepath],