From 14b49aeddda3a66df82d8a7087a5b080aa09a109 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 21 May 2024 10:10:45 +1000 Subject: [PATCH] autotest: neaten Copter Loiter test --- Tools/autotest/arducopter.py | 43 ++++++++++++++---------------------- 1 file changed, 17 insertions(+), 26 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 56ece1f7ed5d3..3d04eceabaac1 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -435,48 +435,39 @@ def LoiterToAlt(self): self.context_push() - ex = None - try: - - self.set_parameters({ - "PLND_ENABLED": 1, - "PLND_TYPE": 4, - }) + self.set_parameters({ + "PLND_ENABLED": 1, + "PLND_TYPE": 4, + }) - self.set_analog_rangefinder_parameters() + self.set_analog_rangefinder_parameters() - self.reboot_sitl() + self.reboot_sitl() - num_wp = self.load_mission("copter_loiter_to_alt.txt") + num_wp = self.load_mission("copter_loiter_to_alt.txt") - self.change_mode('LOITER') + self.change_mode('LOITER') - self.install_terrain_handlers_context() - self.wait_ready_to_arm() + self.install_terrain_handlers_context() + self.wait_ready_to_arm() - self.arm_vehicle() + self.arm_vehicle() - self.change_mode('AUTO') + self.change_mode('AUTO') - self.set_rc(3, 1550) + self.set_rc(3, 1550) - self.wait_current_waypoint(2) + self.wait_current_waypoint(2) - self.set_rc(3, 1500) + self.set_rc(3, 1500) - self.wait_waypoint(0, num_wp-1, timeout=500) + self.wait_waypoint(0, num_wp-1, timeout=500) - self.wait_disarmed() - except Exception as e: - self.print_exception_caught(e) - ex = e + self.wait_disarmed() self.context_pop() self.reboot_sitl() - if ex is not None: - raise ex - # Tests all actions and logic behind the radio failsafe def ThrottleFailsafe(self, side=60, timeout=360): '''Test Throttle Failsafe'''