mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: tidy TestGripperMission
take advantage of new infrastructure
This commit is contained in:
parent
35cb526241
commit
6aa662d5d0
@ -5155,26 +5155,17 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||||||
|
|
||||||
def TestGripperMission(self):
|
def TestGripperMission(self):
|
||||||
'''Test Gripper mission items'''
|
'''Test Gripper mission items'''
|
||||||
self.context_push()
|
num_wp = self.load_mission("copter-gripper-mission.txt")
|
||||||
ex = None
|
self.change_mode('LOITER')
|
||||||
try:
|
self.wait_ready_to_arm()
|
||||||
self.load_mission("copter-gripper-mission.txt")
|
self.assert_vehicle_location_is_at_startup_location()
|
||||||
self.change_mode('LOITER')
|
self.arm_vehicle()
|
||||||
self.wait_ready_to_arm()
|
self.change_mode('AUTO')
|
||||||
self.assert_vehicle_location_is_at_startup_location()
|
self.set_rc(3, 1500)
|
||||||
self.arm_vehicle()
|
self.wait_statustext("Gripper Grabbed", timeout=60)
|
||||||
self.change_mode('AUTO')
|
self.wait_statustext("Gripper Released", timeout=60)
|
||||||
self.set_rc(3, 1500)
|
self.wait_waypoint(num_wp-1, num_wp-1)
|
||||||
self.wait_statustext("Gripper Grabbed", timeout=60)
|
|
||||||
self.wait_statustext("Gripper Released", timeout=60)
|
|
||||||
except Exception as e:
|
|
||||||
self.print_exception_caught(e)
|
|
||||||
self.change_mode('LAND')
|
|
||||||
ex = e
|
|
||||||
self.context_pop()
|
|
||||||
self.wait_disarmed()
|
self.wait_disarmed()
|
||||||
if ex is not None:
|
|
||||||
raise ex
|
|
||||||
|
|
||||||
def SplineLastWaypoint(self):
|
def SplineLastWaypoint(self):
|
||||||
'''Test Spline as last waypoint'''
|
'''Test Spline as last waypoint'''
|
||||||
|
Loading…
Reference in New Issue
Block a user