mirror of https://github.com/ArduPilot/ardupilot
autotest: disable parameters test on Tracker until reboot works
This commit is contained in:
parent
143d069bca
commit
3d0ede499b
|
@ -143,6 +143,7 @@ class AutoTestTracker(AutoTest):
|
||||||
def disabled_tests(self):
|
def disabled_tests(self):
|
||||||
return {
|
return {
|
||||||
"ArmFeatures": "See https://github.com/ArduPilot/ardupilot/issues/10652",
|
"ArmFeatures": "See https://github.com/ArduPilot/ardupilot/issues/10652",
|
||||||
|
"Parameters": "reboot does not work",
|
||||||
}
|
}
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
|
|
|
@ -3914,7 +3914,8 @@ switch value'''
|
||||||
raise AutoTestTimeoutException("Failed to download parameters")
|
raise AutoTestTimeoutException("Failed to download parameters")
|
||||||
m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=1)
|
m = self.mav.recv_match(type='PARAM_VALUE', blocking=True, timeout=1)
|
||||||
if m is None:
|
if m is None:
|
||||||
raise AutoTestTimeoutException("tardy PARAM_VALUE")
|
raise AutoTestTimeoutException("tardy PARAM_VALUE (have %s/%s)" % (
|
||||||
|
str(count), str(expected_count)))
|
||||||
if m.param_index == 65535:
|
if m.param_index == 65535:
|
||||||
self.progress("volunteered parameter: %s" % str(m))
|
self.progress("volunteered parameter: %s" % str(m))
|
||||||
continue
|
continue
|
||||||
|
@ -3937,7 +3938,7 @@ switch value'''
|
||||||
|
|
||||||
def test_parameters_download(self):
|
def test_parameters_download(self):
|
||||||
self.start_subtest("parameter download")
|
self.start_subtest("parameter download")
|
||||||
target_system = 1
|
target_system = self.sysid_thismav()
|
||||||
target_component = 1
|
target_component = 1
|
||||||
(parameters, seq_id) = self.download_parameters(target_system, target_component)
|
(parameters, seq_id) = self.download_parameters(target_system, target_component)
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
|
Loading…
Reference in New Issue