autotest: remove unnecessary try/except from Sprayer test

backport from https://github.com/ArduPilot/ardupilot/pull/23823
This commit is contained in:
Peter Barker 2023-05-19 10:04:11 +10:00 committed by Randy Mackay
parent d9cb0c35d3
commit 737748ee54
1 changed files with 80 additions and 84 deletions

View File

@ -9467,8 +9467,7 @@ class AutoTestCopter(AutoTest):
def Sprayer(self): def Sprayer(self):
"""Test sprayer functionality.""" """Test sprayer functionality."""
self.context_push() self.context_push()
ex = None
try:
rc_ch = 9 rc_ch = 9
pump_ch = 5 pump_ch = 5
spinner_ch = 6 spinner_ch = 6
@ -9563,15 +9562,12 @@ class AutoTestCopter(AutoTest):
0) # p7 0) # p7
self.wait_servo_channel_value(pump_ch, pump_ch_min) self.wait_servo_channel_value(pump_ch, pump_ch_min)
self.progress("Sprayer OK")
except Exception as e:
self.print_exception_caught(e)
ex = e
self.context_pop() self.context_pop()
self.disarm_vehicle(force=True) self.disarm_vehicle(force=True)
self.reboot_sitl() self.reboot_sitl()
if ex:
raise ex self.progress("Sprayer OK")
def tests1a(self): def tests1a(self):
'''return list of all tests''' '''return list of all tests'''
@ -9749,7 +9745,7 @@ class AutoTestCopter(AutoTest):
self.reboot_sitl() self.reboot_sitl()
self.wait_ready_to_arm() self.wait_ready_to_arm()
self.takeoff(alt_min=20, mode='LOITER') self.takeoff(alt_min=20, mode='LOITER')
self.land_and_disarm() self.do_RTL()
self.context_pop() self.context_pop()
self.reboot_sitl() self.reboot_sitl()