mirror of https://github.com/ArduPilot/ardupilot
autotest: adjust tests that need full rate logging
This commit is contained in:
parent
33268bc037
commit
834863fdb7
|
@ -9354,6 +9354,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||||
'''test replay correctness'''
|
'''test replay correctness'''
|
||||||
self.progress("Building Replay")
|
self.progress("Building Replay")
|
||||||
util.build_SITL('tool/Replay', clean=False, configure=False)
|
util.build_SITL('tool/Replay', clean=False, configure=False)
|
||||||
|
self.set_parameters({
|
||||||
|
"LOG_DARM_RATEMAX": 0,
|
||||||
|
"LOG_FILE_RATEMAX": 0,
|
||||||
|
})
|
||||||
|
|
||||||
bits = [
|
bits = [
|
||||||
('GPS', self.test_replay_gps_bit),
|
('GPS', self.test_replay_gps_bit),
|
||||||
|
@ -10208,6 +10212,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||||
self.set_parameters({
|
self.set_parameters({
|
||||||
"LOG_BITMASK": new,
|
"LOG_BITMASK": new,
|
||||||
"LOG_DISARMED": 1,
|
"LOG_DISARMED": 1,
|
||||||
|
"LOG_DARM_RATEMAX": 0,
|
||||||
|
"LOG_FILE_RATEMAX": 0,
|
||||||
})
|
})
|
||||||
path = self.generate_rate_sample_log()
|
path = self.generate_rate_sample_log()
|
||||||
|
|
||||||
|
@ -10230,6 +10236,10 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||||
|
|
||||||
def BaseLoggingRates(self):
|
def BaseLoggingRates(self):
|
||||||
'''ensure messages come out at specific rates'''
|
'''ensure messages come out at specific rates'''
|
||||||
|
self.set_parameters({
|
||||||
|
"LOG_DARM_RATEMAX": 0,
|
||||||
|
"LOG_FILE_RATEMAX": 0,
|
||||||
|
})
|
||||||
path = self.generate_rate_sample_log()
|
path = self.generate_rate_sample_log()
|
||||||
self.delay_sim_time(10) # NFI why this is required
|
self.delay_sim_time(10) # NFI why this is required
|
||||||
self.check_dflog_message_rates(path, {
|
self.check_dflog_message_rates(path, {
|
||||||
|
|
Loading…
Reference in New Issue