From d2bdc949b2e829b8101c3b761d46c4eb15a70ffc Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 9 Dec 2020 10:15:01 +0900 Subject: [PATCH] Tools: Copter.OpticalFlowLimits checks altitude --- Tools/autotest/arducopter.py | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index c3e4fc2264..60539c3a17 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1789,6 +1789,7 @@ class AutoTestCopter(AutoTest): tstart = self.get_sim_time() timeout = 60 + started_climb = False while self.get_sim_time_cached() - tstart < timeout: m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True) spd = math.sqrt(m.vx**2 + m.vy**2) * 0.01 @@ -1805,16 +1806,23 @@ class AutoTestCopter(AutoTest): raise NotAchievedException(("Speed should be limited by" "EKF optical flow limits")) - self.progress("Moving higher") - self.change_alt(60) + # after 30 seconds start climbing + if not started_climb and self.get_sim_time_cached() - tstart > 30: + started_climb = True + self.set_rc(3, 1900) + self.progress("Moving higher") + + # check altitude is not climbing above 35m + if alt > 35: + raise NotAchievedException("Alt should be limited by EKF optical flow limits") - self.wait_groundspeed(10, 100, timeout=60) except Exception as e: self.progress("Caught exception: %s" % self.get_exception_stacktrace(e)) ex = e self.set_rc(2, 1500) + self.set_rc(3, 1500) self.context_pop() self.disarm_vehicle(force=True) self.reboot_sitl()