autotest: let system settle before annoying

Also fly in circles to avoid long flight home
This commit is contained in:
Peter Barker 2021-10-17 22:51:15 +11:00 committed by Peter Barker
parent fda0d16475
commit b9a4902aa6
1 changed files with 5 additions and 2 deletions

View File

@ -3143,14 +3143,17 @@ class AutoTestPlane(AutoTest):
self.fly_mission("ap-circuit.txt", mission_timeout=1200)
def DCMFallback(self):
self.reboot_sitl()
self.delay_sim_time(30)
self.wait_ready_to_arm()
self.arm_vehicle()
self.takeoff(50)
self.change_mode('CIRCLE')
self.context_collect('STATUSTEXT')
self.set_parameter("EK3_POS_I_GATE", 25)
self.set_parameter("EK3_POS_I_GATE", 0)
self.set_parameter("SIM_GPS_HZ", 1)
self.wait_statustext("DCM Active", check_context=True)
self.wait_statustext("DCM Active", check_context=True, timeout=60)
self.wait_statustext("EKF3 Active", check_context=True)
self.wait_statustext("DCM Active", check_context=True)
self.wait_statustext("EKF3 Active", check_context=True)