From b1a0b35401c9552164a5045f414c13bb91084d1d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Sep 2023 18:05:28 +1000 Subject: [PATCH] autotest: tweak Soaring test autotest is failing because our vspeed is below the 0.6 threshold after we exceed the minimal thermal time. Tweak both numbers to try to make test reliable Also re-arrange to try to reduce race-conditions between the Python and C++ code --- Tools/autotest/arduplane.py | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 65fbb0fa77..25bf75b1db 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -2573,11 +2573,6 @@ class AutoTestPlane(AutoTest): self.load_mission('CMAC-soar.txt', strict=False) - self.set_current_waypoint(1) - self.change_mode('AUTO') - self.wait_ready_to_arm() - self.arm_vehicle() - # Enable thermalling RC rc_chan = 0 for i in range(8): @@ -2591,15 +2586,22 @@ class AutoTestPlane(AutoTest): self.set_rc_from_map({ rc_chan: 1900, - 3: 1500, # Use trim airspeed. }) + self.set_parameters({ + "SOAR_VSPEED": 0.55, + "SOAR_MIN_THML_S": 25, + }) + + self.set_current_waypoint(1) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + # Wait to detect thermal self.progress("Waiting for thermal") self.wait_mode('THERMAL', timeout=600) - self.set_parameter("SOAR_VSPEED", 0.6) - # Wait to climb to SOAR_ALT_MAX self.progress("Waiting for climb to max altitude") alt_max = self.get_parameter('SOAR_ALT_MAX')