diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 16e1bdfc1195c..8396aca4e2b28 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -4951,49 +4951,39 @@ def PayloadPlaceMission(self): """Test payload placing in auto.""" self.context_push() - ex = None - try: - self.set_analog_rangefinder_parameters() - self.set_servo_gripper_parameters() - self.reboot_sitl() - - self.load_mission("copter_payload_place.txt") - if self.mavproxy is not None: - self.mavproxy.send('wp list\n') + self.set_analog_rangefinder_parameters() + self.set_servo_gripper_parameters() + self.reboot_sitl() - self.set_parameter("AUTO_OPTIONS", 3) - self.change_mode('AUTO') - self.wait_ready_to_arm() + self.load_mission("copter_payload_place.txt") + if self.mavproxy is not None: + self.mavproxy.send('wp list\n') - self.arm_vehicle() + self.set_parameter("AUTO_OPTIONS", 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() - self.wait_text("Gripper load releas", timeout=90) - dist_limit = 1 - # this is a copy of the point in the mission file: - target_loc = mavutil.location(-35.363106, - 149.165436, - 0, - 0) - dist = self.get_distance(target_loc, self.mav.location()) - self.progress("dist=%f" % (dist,)) - if dist > dist_limit: - raise NotAchievedException("Did not honour target lat/lng (dist=%f want <%f" % - (dist, dist_limit)) + self.arm_vehicle() - self.wait_disarmed() + self.wait_text("Gripper load releas", timeout=90) + dist_limit = 1 + # this is a copy of the point in the mission file: + target_loc = mavutil.location(-35.363106, + 149.165436, + 0, + 0) + dist = self.get_distance(target_loc, self.mav.location()) + self.progress("dist=%f" % (dist,)) + if dist > dist_limit: + raise NotAchievedException("Did not honour target lat/lng (dist=%f want <%f" % + (dist, dist_limit)) - except Exception as e: - self.print_exception_caught(e) - self.disarm_vehicle(force=True) - ex = e + self.wait_disarmed() self.context_pop() self.reboot_sitl() self.progress("All done") - if ex is not None: - raise ex - def Weathervane(self): '''Test copter weathervaning''' # We test nose into wind code paths and yaw direction here and test side into wind