From 60cfc0f016c5338983f5f4d62744e9b624289e10 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 13 Dec 2021 13:26:55 +1100 Subject: [PATCH] autotest: move user_takeoff up to common --- Tools/autotest/arducopter.py | 8 -------- Tools/autotest/common.py | 11 +++++++++++ 2 files changed, 11 insertions(+), 8 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 75ea86f78b..5bb69c8c82 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -123,14 +123,6 @@ class AutoTestCopter(AutoTest): def set_autodisarm_delay(self, delay): self.set_parameter("DISARM_DELAY", delay) - def user_takeoff(self, alt_min=30, timeout=30, max_err=5): - '''takeoff using mavlink takeoff command''' - self.run_cmd( - mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, - p7=alt_min, - ) - self.wait_altitude(alt_min-1, alt_min+max_err, relative=True, timeout=timeout) - def takeoff(self, alt_min=30, takeoff_throttle=1700, diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 942f23ad4d..7eba3b2975 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -11627,6 +11627,17 @@ switch value''' self.progress("Correct value %.4f for %s error %.2f%%" % (v, pname, error_pct)) + def user_takeoff(self, alt_min=30, timeout=30, max_err=5): + '''takeoff using mavlink takeoff command''' + self.run_cmd( + mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, + p7=alt_min, # param7 + ) + self.wait_altitude(alt_min - 1, + (alt_min + max_err), + relative=True, + timeout=timeout) + def ahrstrim_attitude_correctness(self): self.wait_ready_to_arm() HOME = self.sitl_start_location()