mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
autotest: remove copter wait_for_alt
use common wait_altitude instead
This commit is contained in:
parent
86afb1d66b
commit
c99b5e5d47
@ -129,7 +129,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
|
mavutil.mavlink.MAV_CMD_NAV_TAKEOFF,
|
||||||
p7=alt_min,
|
p7=alt_min,
|
||||||
)
|
)
|
||||||
self.wait_for_alt(alt_min, timeout=timeout, max_err=max_err)
|
self.wait_altitude(alt_min-1, alt_min+max_err, relative=True, timeout=timeout)
|
||||||
|
|
||||||
def takeoff(self,
|
def takeoff(self,
|
||||||
alt_min=30,
|
alt_min=30,
|
||||||
@ -149,17 +149,10 @@ class AutoTestCopter(AutoTest):
|
|||||||
self.user_takeoff(alt_min=alt_min, timeout=timeout, max_err=max_err)
|
self.user_takeoff(alt_min=alt_min, timeout=timeout, max_err=max_err)
|
||||||
else:
|
else:
|
||||||
self.set_rc(3, takeoff_throttle)
|
self.set_rc(3, takeoff_throttle)
|
||||||
self.wait_for_alt(alt_min=alt_min, timeout=timeout, max_err=max_err)
|
self.wait_altitude(alt_min-1, alt_min+max_err, relative=True, timeout=timeout)
|
||||||
self.hover()
|
self.hover()
|
||||||
self.progress("TAKEOFF COMPLETE")
|
self.progress("TAKEOFF COMPLETE")
|
||||||
|
|
||||||
def wait_for_alt(self, alt_min=30, timeout=30, max_err=5):
|
|
||||||
"""Wait for minimum altitude to be reached."""
|
|
||||||
self.wait_altitude(alt_min - 1,
|
|
||||||
(alt_min + max_err),
|
|
||||||
relative=True,
|
|
||||||
timeout=timeout)
|
|
||||||
|
|
||||||
def land_and_disarm(self, timeout=60):
|
def land_and_disarm(self, timeout=60):
|
||||||
"""Land the quad."""
|
"""Land the quad."""
|
||||||
self.progress("STARTING LANDING")
|
self.progress("STARTING LANDING")
|
||||||
@ -171,7 +164,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
|
||||||
alt = m.relative_alt / 1000.0 # mm -> m
|
alt = m.relative_alt / 1000.0 # mm -> m
|
||||||
if alt > min_alt:
|
if alt > min_alt:
|
||||||
self.wait_for_alt(min_alt, timeout=timeout)
|
self.wait_altitude(min_alt-1, min_alt+5, relative=True, timeout=timeout)
|
||||||
# self.wait_statustext("SIM Hit ground", timeout=timeout)
|
# self.wait_statustext("SIM Hit ground", timeout=timeout)
|
||||||
self.wait_disarmed()
|
self.wait_disarmed()
|
||||||
|
|
||||||
@ -2100,7 +2093,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
self.progress("Regaining altitude")
|
self.progress("Regaining altitude")
|
||||||
self.change_mode('ALT_HOLD')
|
self.change_mode('ALT_HOLD')
|
||||||
self.wait_for_alt(20, max_err=40)
|
self.wait_altitude(19, 60, relative=True)
|
||||||
|
|
||||||
self.progress("Flipping in pitch")
|
self.progress("Flipping in pitch")
|
||||||
self.set_rc(2, 1700)
|
self.set_rc(2, 1700)
|
||||||
@ -2440,7 +2433,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
raise NotAchievedException("AUTOTUNE gains not present in pilot testing")
|
raise NotAchievedException("AUTOTUNE gains not present in pilot testing")
|
||||||
# land without changing mode
|
# land without changing mode
|
||||||
self.set_rc(3, 1000)
|
self.set_rc(3, 1000)
|
||||||
self.wait_for_alt(0)
|
self.wait_altitude(-1, 5, relative=True)
|
||||||
self.wait_disarmed()
|
self.wait_disarmed()
|
||||||
# Check gains are still there after disarm
|
# Check gains are still there after disarm
|
||||||
if (rlld == self.get_parameter("ATC_RAT_RLL_D") or
|
if (rlld == self.get_parameter("ATC_RAT_RLL_D") or
|
||||||
|
@ -167,7 +167,7 @@ class AutoTestHelicopter(AutoTestCopter):
|
|||||||
self.user_takeoff(alt_min=alt_min)
|
self.user_takeoff(alt_min=alt_min)
|
||||||
else:
|
else:
|
||||||
self.set_rc(3, takeoff_throttle)
|
self.set_rc(3, takeoff_throttle)
|
||||||
self.wait_for_alt(alt_min=alt_min, timeout=timeout)
|
self.wait_altitude(alt_min-1, alt_min+5, relative=True, timeout=timeout)
|
||||||
self.hover()
|
self.hover()
|
||||||
self.progress("TAKEOFF COMPLETE")
|
self.progress("TAKEOFF COMPLETE")
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user