Browse Source

autotest: reset mission on takeoff for quadplanes

apm_2208
Andrew Tridgell 3 years ago
parent
commit
151f17d563
  1. 2
      Tools/autotest/arduplane.py
  2. 1
      Tools/autotest/common.py
  3. 2
      Tools/autotest/quadplane.py

2
Tools/autotest/arduplane.py

@ -614,6 +614,7 @@ class AutoTestPlane(AutoTest): @@ -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)
@ -784,6 +785,7 @@ class AutoTestPlane(AutoTest): @@ -784,6 +785,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."""

1
Tools/autotest/common.py

@ -6790,6 +6790,7 @@ Also, ignores heartbeats not from our target system''' @@ -6790,6 +6790,7 @@ Also, ignores heartbeats not from our target system'''
try:
self.check_rc_defaults()
self.change_mode(self.default_mode())
self.set_current_waypoint(0, check_afterwards=False)
self.drain_mav()
self.drain_all_pexpects()

2
Tools/autotest/quadplane.py

@ -446,6 +446,7 @@ class AutoTestQuadPlane(AutoTest): @@ -446,6 +446,7 @@ class AutoTestQuadPlane(AutoTest):
def takeoff(self, height, mode):
"""climb to specified height and set throttle to 1500"""
self.set_current_waypoint(0, check_afterwards=False)
self.change_mode(mode)
self.wait_ready_to_arm()
self.arm_vehicle()
@ -470,6 +471,7 @@ class AutoTestQuadPlane(AutoTest): @@ -470,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…
Cancel
Save