mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Tools: plane: GCSFailsafe test: cleanup timeouts
This commit is contained in:
parent
2ffae80866
commit
11fb7c64e0
@ -1177,8 +1177,7 @@ class AutoTestPlane(AutoTest):
|
||||
})
|
||||
self.progress("Disconnecting GCS")
|
||||
self.set_heartbeat_rate(0)
|
||||
self.delay_sim_time(5)
|
||||
self.wait_mode("RTL")
|
||||
self.wait_mode("RTL", timeout=5)
|
||||
self.set_heartbeat_rate(self.speedup)
|
||||
self.end_subtest("Completed RTL Failsafe test")
|
||||
|
||||
@ -1191,8 +1190,7 @@ class AutoTestPlane(AutoTest):
|
||||
self.takeoff()
|
||||
self.progress("Disconnecting GCS")
|
||||
self.set_heartbeat_rate(0)
|
||||
self.delay_sim_time(5)
|
||||
self.wait_mode("FBWA")
|
||||
self.wait_mode("FBWA", timeout=5)
|
||||
self.set_heartbeat_rate(self.speedup)
|
||||
self.end_subtest("Completed FBWA Failsafe test")
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user