From 834863fdb7ae9a61d5dc66f6725743ef3abd29b1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 29 Sep 2024 11:02:10 +1000 Subject: [PATCH] autotest: adjust tests that need full rate logging --- Tools/autotest/arducopter.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 1747c72fc9..8a3d11b6f1 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -9354,6 +9354,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite): '''test replay correctness''' self.progress("Building Replay") util.build_SITL('tool/Replay', clean=False, configure=False) + self.set_parameters({ + "LOG_DARM_RATEMAX": 0, + "LOG_FILE_RATEMAX": 0, + }) bits = [ ('GPS', self.test_replay_gps_bit), @@ -10208,6 +10212,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite): self.set_parameters({ "LOG_BITMASK": new, "LOG_DISARMED": 1, + "LOG_DARM_RATEMAX": 0, + "LOG_FILE_RATEMAX": 0, }) path = self.generate_rate_sample_log() @@ -10230,6 +10236,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite): def BaseLoggingRates(self): '''ensure messages come out at specific rates''' + self.set_parameters({ + "LOG_DARM_RATEMAX": 0, + "LOG_FILE_RATEMAX": 0, + }) path = self.generate_rate_sample_log() self.delay_sim_time(10) # NFI why this is required self.check_dflog_message_rates(path, {