mirror of https://github.com/ArduPilot/ardupilot
autotest: remove unnecessary try/except from Sprayer test
backport from https://github.com/ArduPilot/ardupilot/pull/23823
This commit is contained in:
parent
d9cb0c35d3
commit
737748ee54
|
@ -9467,111 +9467,107 @@ 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
|
|
||||||
pump_ch = 5
|
|
||||||
spinner_ch = 6
|
|
||||||
pump_ch_min = 1050
|
|
||||||
pump_ch_trim = 1520
|
|
||||||
pump_ch_max = 1950
|
|
||||||
spinner_ch_min = 975
|
|
||||||
spinner_ch_trim = 1510
|
|
||||||
spinner_ch_max = 1975
|
|
||||||
|
|
||||||
self.set_parameters({
|
rc_ch = 9
|
||||||
"SPRAY_ENABLE": 1,
|
pump_ch = 5
|
||||||
|
spinner_ch = 6
|
||||||
|
pump_ch_min = 1050
|
||||||
|
pump_ch_trim = 1520
|
||||||
|
pump_ch_max = 1950
|
||||||
|
spinner_ch_min = 975
|
||||||
|
spinner_ch_trim = 1510
|
||||||
|
spinner_ch_max = 1975
|
||||||
|
|
||||||
"SERVO%u_FUNCTION" % pump_ch: 22,
|
self.set_parameters({
|
||||||
"SERVO%u_MIN" % pump_ch: pump_ch_min,
|
"SPRAY_ENABLE": 1,
|
||||||
"SERVO%u_TRIM" % pump_ch: pump_ch_trim,
|
|
||||||
"SERVO%u_MAX" % pump_ch: pump_ch_max,
|
|
||||||
|
|
||||||
"SERVO%u_FUNCTION" % spinner_ch: 23,
|
"SERVO%u_FUNCTION" % pump_ch: 22,
|
||||||
"SERVO%u_MIN" % spinner_ch: spinner_ch_min,
|
"SERVO%u_MIN" % pump_ch: pump_ch_min,
|
||||||
"SERVO%u_TRIM" % spinner_ch: spinner_ch_trim,
|
"SERVO%u_TRIM" % pump_ch: pump_ch_trim,
|
||||||
"SERVO%u_MAX" % spinner_ch: spinner_ch_max,
|
"SERVO%u_MAX" % pump_ch: pump_ch_max,
|
||||||
|
|
||||||
"SIM_SPR_ENABLE": 1,
|
"SERVO%u_FUNCTION" % spinner_ch: 23,
|
||||||
"SIM_SPR_PUMP": pump_ch,
|
"SERVO%u_MIN" % spinner_ch: spinner_ch_min,
|
||||||
"SIM_SPR_SPIN": spinner_ch,
|
"SERVO%u_TRIM" % spinner_ch: spinner_ch_trim,
|
||||||
|
"SERVO%u_MAX" % spinner_ch: spinner_ch_max,
|
||||||
|
|
||||||
"RC%u_OPTION" % rc_ch: 15,
|
"SIM_SPR_ENABLE": 1,
|
||||||
"LOG_DISARMED": 1,
|
"SIM_SPR_PUMP": pump_ch,
|
||||||
})
|
"SIM_SPR_SPIN": spinner_ch,
|
||||||
|
|
||||||
self.reboot_sitl()
|
"RC%u_OPTION" % rc_ch: 15,
|
||||||
|
"LOG_DISARMED": 1,
|
||||||
|
})
|
||||||
|
|
||||||
self.wait_ready_to_arm()
|
self.reboot_sitl()
|
||||||
self.arm_vehicle()
|
|
||||||
|
|
||||||
self.progress("test bootup state - it's zero-output!")
|
self.wait_ready_to_arm()
|
||||||
self.wait_servo_channel_value(spinner_ch, 0)
|
self.arm_vehicle()
|
||||||
self.wait_servo_channel_value(pump_ch, 0)
|
|
||||||
|
|
||||||
self.progress("Enable sprayer")
|
self.progress("test bootup state - it's zero-output!")
|
||||||
self.set_rc(rc_ch, 2000)
|
self.wait_servo_channel_value(spinner_ch, 0)
|
||||||
|
self.wait_servo_channel_value(pump_ch, 0)
|
||||||
|
|
||||||
self.progress("Testing zero-speed state")
|
self.progress("Enable sprayer")
|
||||||
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
|
self.set_rc(rc_ch, 2000)
|
||||||
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
|
||||||
|
|
||||||
self.progress("Testing turning it off")
|
self.progress("Testing zero-speed state")
|
||||||
self.set_rc(rc_ch, 1000)
|
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
|
||||||
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
|
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
||||||
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
|
||||||
|
|
||||||
self.progress("Testing turning it back on")
|
self.progress("Testing turning it off")
|
||||||
self.set_rc(rc_ch, 2000)
|
self.set_rc(rc_ch, 1000)
|
||||||
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
|
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
|
||||||
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
||||||
|
|
||||||
self.takeoff(30, mode='LOITER')
|
self.progress("Testing turning it back on")
|
||||||
|
self.set_rc(rc_ch, 2000)
|
||||||
|
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
|
||||||
|
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
||||||
|
|
||||||
self.progress("Testing speed-ramping")
|
self.takeoff(30, mode='LOITER')
|
||||||
self.set_rc(1, 1700) # start driving forward
|
|
||||||
|
|
||||||
# this is somewhat empirical...
|
self.progress("Testing speed-ramping")
|
||||||
self.wait_servo_channel_value(pump_ch, 1458, timeout=60)
|
self.set_rc(1, 1700) # start driving forward
|
||||||
|
|
||||||
self.progress("Turning it off again")
|
# this is somewhat empirical...
|
||||||
self.set_rc(rc_ch, 1000)
|
self.wait_servo_channel_value(pump_ch, 1458, timeout=60)
|
||||||
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
|
|
||||||
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
|
||||||
|
|
||||||
self.start_subtest("Checking mavlink commands")
|
self.progress("Turning it off again")
|
||||||
self.progress("Starting Sprayer")
|
self.set_rc(rc_ch, 1000)
|
||||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER,
|
self.wait_servo_channel_value(spinner_ch, spinner_ch_min)
|
||||||
1, # p1
|
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
||||||
0, # p2
|
|
||||||
0, # p3
|
|
||||||
0, # p4
|
|
||||||
0, # p5
|
|
||||||
0, # p6
|
|
||||||
0) # p7
|
|
||||||
|
|
||||||
self.progress("Testing speed-ramping")
|
self.start_subtest("Checking mavlink commands")
|
||||||
self.wait_servo_channel_value(pump_ch, 1458, timeout=60, comparator=operator.gt)
|
self.progress("Starting Sprayer")
|
||||||
self.start_subtest("Stopping Sprayer")
|
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER,
|
||||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER,
|
1, # p1
|
||||||
0, # p1
|
0, # p2
|
||||||
0, # p2
|
0, # p3
|
||||||
0, # p3
|
0, # p4
|
||||||
0, # p4
|
0, # p5
|
||||||
0, # p5
|
0, # p6
|
||||||
0, # p6
|
0) # p7
|
||||||
0) # p7
|
|
||||||
self.wait_servo_channel_value(pump_ch, pump_ch_min)
|
self.progress("Testing speed-ramping")
|
||||||
|
self.wait_servo_channel_value(pump_ch, 1458, timeout=60, comparator=operator.gt)
|
||||||
|
self.start_subtest("Stopping Sprayer")
|
||||||
|
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER,
|
||||||
|
0, # p1
|
||||||
|
0, # p2
|
||||||
|
0, # p3
|
||||||
|
0, # p4
|
||||||
|
0, # p5
|
||||||
|
0, # p6
|
||||||
|
0) # p7
|
||||||
|
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()
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue