autotest: stop using MAVProxy to change mode

This commit is contained in:
Peter Barker 2021-02-19 20:35:07 +11:00 committed by Peter Barker
parent 05c9b79a5e
commit d4aef2dba8
3 changed files with 18 additions and 31 deletions

View File

@ -1721,7 +1721,7 @@ class AutoTestCopter(AutoTest):
self.set_parameter('SIM_SPEEDUP', 1)
self.progress("Flipping in roll")
self.set_rc(1, 1700)
self.mavproxy.send('mode FLIP\n') # don't wait for heartbeat!
self.send_cmd_do_set_mode('FLIP') # don't wait for success
self.wait_attitude(despitch=0, desroll=45, tolerance=30)
self.wait_attitude(despitch=0, desroll=90, tolerance=30)
self.wait_attitude(despitch=0, desroll=-45, tolerance=30)
@ -1737,7 +1737,7 @@ class AutoTestCopter(AutoTest):
self.progress("Flipping in pitch")
self.set_rc(2, 1700)
self.mavproxy.send('mode FLIP\n') # don't wait for heartbeat!
self.send_cmd_do_set_mode('FLIP') # don't wait for success
self.wait_attitude(despitch=45, desroll=0, tolerance=30)
# can't check roll here as it flips from 0 to -180..
self.wait_attitude(despitch=90, tolerance=30)
@ -3556,19 +3556,18 @@ class AutoTestCopter(AutoTest):
ex = None
try:
self.load_mission("copter-gripper-mission.txt")
self.mavproxy.send('mode loiter\n')
self.change_mode('LOITER')
self.wait_ready_to_arm()
self.assert_vehicle_location_is_at_startup_location()
self.arm_vehicle()
self.mavproxy.send('mode auto\n')
self.wait_mode('AUTO')
self.change_mode('AUTO')
self.set_rc(3, 1500)
self.wait_statustext("Gripper Grabbed", timeout=60)
self.wait_statustext("Gripper Released", timeout=60)
except Exception as e:
self.progress("Exception caught: %s" % (
self.get_exception_stacktrace(e)))
self.mavproxy.send('mode land\n')
self.change_mode('LAND')
ex = e
self.context_pop()
self.wait_disarmed()
@ -3580,7 +3579,7 @@ class AutoTestCopter(AutoTest):
ex = None
try:
self.load_mission("copter-spline-last-waypoint.txt")
self.mavproxy.send('mode loiter\n')
self.change_mode('LOITER')
self.wait_ready_to_arm()
self.arm_vehicle()
self.change_mode('AUTO')

View File

@ -178,8 +178,7 @@ class AutoTestPlane(AutoTest):
def fly_LOITER(self, num_circles=4):
"""Loiter where we are."""
self.progress("Testing LOITER for %u turns" % num_circles)
self.mavproxy.send('loiter\n')
self.wait_mode('LOITER')
self.change_mode('LOITER')
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
initial_alt = m.alt
@ -196,8 +195,7 @@ class AutoTestPlane(AutoTest):
self.progress("Final altitude %u initial %u\n" %
(final_alt, initial_alt))
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
if abs(final_alt - initial_alt) > 20:
raise NotAchievedException("Failed to maintain altitude")
@ -207,8 +205,7 @@ class AutoTestPlane(AutoTest):
def fly_CIRCLE(self, num_circles=1):
"""Circle where we are."""
self.progress("Testing CIRCLE for %u turns" % num_circles)
self.mavproxy.send('mode CIRCLE\n')
self.wait_mode('CIRCLE')
self.change_mode('CIRCLE')
m = self.mav.recv_match(type='VFR_HUD', blocking=True)
initial_alt = m.alt
@ -225,8 +222,7 @@ class AutoTestPlane(AutoTest):
self.progress("Final altitude %u initial %u\n" %
(final_alt, initial_alt))
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
if abs(final_alt - initial_alt) > 20:
raise NotAchievedException("Failed to maintain altitude")
@ -252,8 +248,7 @@ class AutoTestPlane(AutoTest):
def change_altitude(self, altitude, accuracy=30):
"""Get to a given altitude."""
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
alt_error = self.mav.messages['VFR_HUD'].alt - altitude
if alt_error > 0:
self.set_rc(2, 2000)
@ -389,14 +384,12 @@ class AutoTestPlane(AutoTest):
yaw_rate_radians,
thrust)
except Exception as e:
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
self.set_rc(3, 1700)
raise e
# back to FBWA
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
self.set_rc(3, 1700)
self.wait_level_flight()
@ -422,8 +415,7 @@ class AutoTestPlane(AutoTest):
self.wait_roll(0, accuracy=5)
# back to FBWA
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
self.set_rc(3, 1700)
return self.wait_level_flight()
@ -447,8 +439,7 @@ class AutoTestPlane(AutoTest):
self.set_rc(1, 1500)
# back to FBWA
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
self.wait_level_flight()
@ -465,8 +456,7 @@ class AutoTestPlane(AutoTest):
self.set_rc(2, 1500)
# back to FBWA
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
self.set_rc(3, 1700)
return self.wait_level_flight()
@ -524,8 +514,7 @@ class AutoTestPlane(AutoTest):
(final_alt, initial_alt))
# back to FBWA
self.mavproxy.send('mode FBWA\n')
self.wait_mode('FBWA')
self.change_mode('FBWA')
if abs(final_alt - initial_alt) > 20:
raise NotAchievedException("Failed to maintain altitude")

View File

@ -288,8 +288,7 @@ class AutoTestQuadPlane(AutoTest):
self.mavproxy.expect('Requesting [0-9]+ waypoints')
self.wait_ready_to_arm()
self.arm_vehicle()
self.mavproxy.send('mode AUTO\n')
self.wait_mode('AUTO')
self.change_mode('AUTO')
self.wait_waypoint(1, 19, max_dist=60, timeout=1200)
self.wait_disarmed(timeout=120) # give quadplane a long time to land