Tools: update arducopter.py to use new wait functions

This commit is contained in:
Pierre Kancir 2019-07-08 18:15:02 +02:00 committed by Peter Barker
parent 2d65cbd884
commit e4eebce5a6

View File

@ -267,16 +267,14 @@ class AutoTestCopter(AutoTest):
def change_alt(self, alt_min, climb_throttle=1920, descend_throttle=1080):
"""Change altitude."""
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
alt = m.relative_alt / 1000.0 # mm -> m
if alt < alt_min:
self.progress("Rise to alt:%u from %u" % (alt_min, alt))
def adjust_altitude(current_alt, target_alt, accuracy):
if math.fabs(current_alt - target_alt) <= accuracy:
self.hover()
elif current_alt < target_alt:
self.set_rc(3, climb_throttle)
self.wait_altitude(alt_min, (alt_min + 5), relative=True)
else:
self.progress("Lower to alt:%u from %u" % (alt_min, alt))
self.set_rc(3, descend_throttle)
self.wait_altitude((alt_min - 5), alt_min, relative=True)
self.wait_altitude((alt_min - 5), alt_min, relative=True, called_function=lambda current_alt, target_alt: adjust_altitude(current_alt, target_alt, 1))
self.hover()
def setGCSfailsafe(self,paramValue=0):
@ -382,7 +380,7 @@ class AutoTestCopter(AutoTest):
self.progress("timeleft = %u" % time_left)
if time_left < 20:
time_left = 20
self.wait_altitude(-10, 10, time_left, relative=True)
self.wait_altitude(-10, 10, timeout=time_left, relative=True)
self.set_rc(3, 1500)
self.save_wp()
@ -4158,7 +4156,7 @@ class AutoTestCopter(AutoTest):
self.set_rc(3, 1500)
# move away a little
self.set_rc(2, 1550)
self.wait_distance(5)
self.wait_distance(5, accuracy=1)
self.set_rc(2, 1500)
self.mavproxy.send('mode loiter\n')
self.wait_mode('LOITER')