mirror of https://github.com/ArduPilot/ardupilot
autotest: correct fettec test
need to wait for accels/gyros to be healthy
This commit is contained in:
parent
4591895540
commit
e494c40b61
|
@ -9190,6 +9190,7 @@ class AutoTestCopter(AutoTest):
|
||||||
self.context_push()
|
self.context_push()
|
||||||
self.set_parameter("SERVO_FTW_MASK", mask)
|
self.set_parameter("SERVO_FTW_MASK", mask)
|
||||||
self.reboot_sitl()
|
self.reboot_sitl()
|
||||||
|
self.delay_sim_time(12) # allow accels/gyros to be happy
|
||||||
tstart = self.get_sim_time()
|
tstart = self.get_sim_time()
|
||||||
while True:
|
while True:
|
||||||
if self.get_sim_time_cached() - tstart > 20:
|
if self.get_sim_time_cached() - tstart > 20:
|
||||||
|
|
Loading…
Reference in New Issue