From 77f98b4072974a6f60a15d502b760aac838da77f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 14 May 2022 16:02:17 +1000 Subject: [PATCH] autotest: reset mission on takeoff for quadplanes --- Tools/autotest/arduplane.py | 2 ++ Tools/autotest/quadplane.py | 1 + 2 files changed, 3 insertions(+) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index dcf351fb70..679ea7e7d4 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -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.""" diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 62b07de753..c6ca8227a3 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -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."""