diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 9a88c19714..f6f8e7a73b 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -5155,26 +5155,17 @@ class AutoTestCopter(vehicle_test_suite.TestSuite): def TestGripperMission(self): '''Test Gripper mission items''' - self.context_push() - ex = None - try: - self.load_mission("copter-gripper-mission.txt") - self.change_mode('LOITER') - self.wait_ready_to_arm() - self.assert_vehicle_location_is_at_startup_location() - self.arm_vehicle() - 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.print_exception_caught(e) - self.change_mode('LAND') - ex = e - self.context_pop() + num_wp = self.load_mission("copter-gripper-mission.txt") + self.change_mode('LOITER') + self.wait_ready_to_arm() + self.assert_vehicle_location_is_at_startup_location() + self.arm_vehicle() + self.change_mode('AUTO') + self.set_rc(3, 1500) + self.wait_statustext("Gripper Grabbed", timeout=60) + self.wait_statustext("Gripper Released", timeout=60) + self.wait_waypoint(num_wp-1, num_wp-1) self.wait_disarmed() - if ex is not None: - raise ex def SplineLastWaypoint(self): '''Test Spline as last waypoint'''