mirror of https://github.com/ArduPilot/ardupilot
autotest: reset mission on takeoff for quadplanes
This commit is contained in:
parent
1f7354951d
commit
d14897b1b1
|
@ -614,6 +614,7 @@ class AutoTestPlane(AutoTest):
|
|||
self.wait_servo_channel_value(2, deepstall_elevator_pwm)
|
||||
|
||||
self.disarm_wait(timeout=120)
|
||||
self.set_current_waypoint(0, check_afterwards=False)
|
||||
|
||||
self.progress("Flying home")
|
||||
self.takeoff(100)
|
||||
|
@ -749,6 +750,7 @@ class AutoTestPlane(AutoTest):
|
|||
# tend to miss the final waypoint by a fair bit, and
|
||||
# this is probably too noisy anyway?
|
||||
self.wait_disarmed(timeout=timeout)
|
||||
self.set_current_waypoint(0, check_afterwards=False)
|
||||
|
||||
def fly_flaps(self):
|
||||
"""Test flaps functionality."""
|
||||
|
|
|
@ -471,6 +471,7 @@ class AutoTestQuadPlane(AutoTest):
|
|||
self.change_mode("AUTO")
|
||||
self.set_current_waypoint(7)
|
||||
self.wait_disarmed(timeout=timeout)
|
||||
self.set_current_waypoint(0, check_afterwards=False)
|
||||
|
||||
def wait_level_flight(self, accuracy=5, timeout=30):
|
||||
"""Wait for level flight."""
|
||||
|
|
Loading…
Reference in New Issue