From 61bb5754225aa8de817f303b60c6281a2632bda9 Mon Sep 17 00:00:00 2001 From: m Date: Wed, 20 Apr 2022 18:08:55 +0300 Subject: [PATCH] autotest: Fix watch_altitude_maintained for Copter --- Tools/autotest/arducopter.py | 16 +++------------- Tools/autotest/common.py | 8 ++++++++ 2 files changed, 11 insertions(+), 13 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 1294e51ae8..082e393045 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -264,27 +264,17 @@ class AutoTestCopter(AutoTest): self.do_RTL() - def watch_altitude_maintained(self, min_alt, max_alt, timeout=10): - '''watch alt, relative alt must remain between min_alt and max_alt''' - tstart = self.get_sim_time_cached() - while True: - if self.get_sim_time_cached() - tstart > timeout: - return - m = self.mav.recv_match(type='VFR_HUD', blocking=True) - if m.alt <= min_alt: - raise NotAchievedException("Altitude not maintained: want >%f got=%f" % (min_alt, m.alt)) - def ModeAltHold(self): '''Test AltHold Mode''' self.takeoff(10, mode="ALT_HOLD") - self.watch_altitude_maintained(9, 11, timeout=5) + self.watch_altitude_maintained(altitude_min=9, altitude_max=11) # feed in full elevator and aileron input and make sure we # retain altitude: self.set_rc_from_map({ 1: 1000, 2: 1000, }) - self.watch_altitude_maintained(9, 11, timeout=5) + self.watch_altitude_maintained(altitude_min=9, altitude_max=11) self.set_rc_from_map({ 1: 1500, 2: 1500, @@ -4572,7 +4562,7 @@ class AutoTestCopter(AutoTest): self.change_mode("STABILIZE") self.change_mode("GUIDED") self.set_rc(3, 1700) - self.watch_altitude_maintained(-1, 0.2) # should not take off in guided + self.watch_altitude_maintained(altitude_min=-1, altitude_max=0.2) # should not take off in guided self.run_cmd_do_set_mode( "ACRO", want_result=mavutil.mavlink.MAV_RESULT_FAILED) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index f82c51b49f..cbb9e75b13 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -5837,6 +5837,14 @@ class AutoTest(ABC): **kwargs ) + def watch_altitude_maintained(self, altitude_min, altitude_max, minimum_duration=5, relative=True): + """Watch altitude is maintained or not between altitude_min and altitude_max during minimum_duration""" + return self.wait_altitude(altitude_min=altitude_min, + altitude_max=altitude_max, + relative=relative, + minimum_duration=minimum_duration, + timeout=minimum_duration + 1) + def wait_climbrate(self, speed_min, speed_max, timeout=30, **kwargs): """Wait for a given vertical rate.""" assert speed_min <= speed_max, "Minimum speed should be less than maximum speed."