mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-05 21:23:58 -04:00
autotest: Fix the climb-before-turn test
This commit is contained in:
parent
717b06d635
commit
f6fc6d22da
@ -1650,7 +1650,7 @@ class AutoTestPlane(AutoTest):
|
|||||||
self.wait_ready_to_arm()
|
self.wait_ready_to_arm()
|
||||||
self.set_parameter("FLIGHT_OPTIONS", 0)
|
self.set_parameter("FLIGHT_OPTIONS", 0)
|
||||||
self.set_parameter("ALT_HOLD_RTL", 8000)
|
self.set_parameter("ALT_HOLD_RTL", 8000)
|
||||||
takeoff_alt = 40
|
takeoff_alt = 10
|
||||||
self.takeoff(alt=takeoff_alt)
|
self.takeoff(alt=takeoff_alt)
|
||||||
self.change_mode("CRUISE")
|
self.change_mode("CRUISE")
|
||||||
self.wait_distance_to_home(500, 1000, timeout=60)
|
self.wait_distance_to_home(500, 1000, timeout=60)
|
||||||
|
Loading…
Reference in New Issue
Block a user