mirror of https://github.com/ArduPilot/ardupilot
Tools: autotest: make plane receiver-healthy check more reliable
This commit is contained in:
parent
34ef247449
commit
1af76bbf60
|
@ -839,9 +839,11 @@ class AutoTestPlane(AutoTest):
|
||||||
raise NotAchievedException("Sensor healthy when it shouldn't be")
|
raise NotAchievedException("Sensor healthy when it shouldn't be")
|
||||||
self.progress("Making RC work again")
|
self.progress("Making RC work again")
|
||||||
self.set_parameter("SIM_RC_FAIL", 0)
|
self.set_parameter("SIM_RC_FAIL", 0)
|
||||||
|
# have to allow time for RC to be fetched from SITL
|
||||||
self.progress("Giving receiver time to recover")
|
self.progress("Giving receiver time to recover")
|
||||||
for i in range(1, 10):
|
self.delay_sim_time(0.5)
|
||||||
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
self.drain_mav_unparsed()
|
||||||
|
m = self.mav.recv_match(type='SYS_STATUS', blocking=True)
|
||||||
self.progress("Testing receiver enabled")
|
self.progress("Testing receiver enabled")
|
||||||
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
if (not (m.onboard_control_sensors_enabled & receiver_bit)):
|
||||||
raise NotAchievedException("Receiver not enabled")
|
raise NotAchievedException("Receiver not enabled")
|
||||||
|
|
Loading…
Reference in New Issue