autotest: move user_takeoff up to common

This commit is contained in:
Peter Barker 2021-12-13 13:26:55 +11:00 committed by Peter Barker
parent f787e940b3
commit 60cfc0f016
2 changed files with 11 additions and 8 deletions

View File

@ -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,

View File

@ -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()