mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tools: autotest: increase timeout on pid tuning
This commit is contained in:
parent
f23c6e1624
commit
b1bbe09602
@ -2287,12 +2287,12 @@ switch value'''
|
|||||||
|
|
||||||
def test_pid_tuning(self):
|
def test_pid_tuning(self):
|
||||||
self.progress("making sure we're not getting PID_TUNING messages")
|
self.progress("making sure we're not getting PID_TUNING messages")
|
||||||
m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=1)
|
m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=5)
|
||||||
if m is not None:
|
if m is not None:
|
||||||
raise PreconditionFailedException("Receiving PID_TUNING already")
|
raise PreconditionFailedException("Receiving PID_TUNING already")
|
||||||
self.set_parameter("GCS_PID_MASK", 1)
|
self.set_parameter("GCS_PID_MASK", 1)
|
||||||
self.progress("making sure we are now getting PID_TUNING messages")
|
self.progress("making sure we are now getting PID_TUNING messages")
|
||||||
m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=1)
|
m = self.mav.recv_match(type='PID_TUNING', blocking=True, timeout=5)
|
||||||
if m is None:
|
if m is None:
|
||||||
raise PreconditionFailedException("Did not start to get PID_TUNING message")
|
raise PreconditionFailedException("Did not start to get PID_TUNING message")
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user