autotest: tidy various Rover autotests

autotest: tidy Sprayer test

autotest: tidy rover AC_Avoidance test

autotest: tidy rover ModeSwitch test

autotest: tidy rover AuxModeSwitch

autotest: tidy rover RCOverrides test

autotest: tidy rover MANUAL_CONTROL test

autotest: tidy rover PolyFenceObjectAvoidance test
This commit is contained in:
Peter Barker 2024-07-26 20:46:18 +10:00 committed by Peter Barker
parent 763292780a
commit 605a9d34e3

View File

@ -227,9 +227,6 @@ class AutoTestRover(vehicle_test_suite.TestSuite):
def Sprayer(self):
"""Test sprayer functionality."""
self.context_push()
ex = None
try:
rc_ch = 5
pump_ch = 5
spinner_ch = 6
@ -318,17 +315,10 @@ class AutoTestRover(vehicle_test_suite.TestSuite):
self.start_subtest("Stopping Sprayer")
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=0)
self.wait_servo_channel_value(pump_ch, pump_ch_min)
self.set_rc(3, 1000) # start driving forward
self.set_rc(3, 1000) # stop driving forward
self.progress("Sprayer OK")
except Exception as e:
self.print_exception_caught(e)
ex = e
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl()
if ex:
raise ex
self.disarm_vehicle()
def DriveMaxRCIN(self, timeout=30):
"""Drive rover at max RC inputs"""
@ -538,9 +528,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
def AC_Avoidance(self):
'''Test AC Avoidance switch'''
self.context_push()
ex = None
try:
self.load_fence("rover-fence-ac-avoid.txt")
self.set_parameters({
"FENCE_ENABLE": 0,
@ -564,16 +551,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.wait_groundspeed(0, 0.7, timeout=60)
# watch for speed zero
self.wait_groundspeed(0, 0.2, timeout=120)
except Exception as e:
self.print_exception_caught(e)
ex = e
self.disarm_vehicle(force=True)
self.context_pop()
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)
self.reboot_sitl()
if ex:
raise ex
self.disarm_vehicle()
def ServoRelayEvents(self):
'''Test ServoRelayEvents'''
@ -745,9 +723,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
def ModeSwitch(self):
''''Set modes via modeswitch'''
self.context_push()
ex = None
try:
self.set_parameter("MODE_CH", 8)
self.set_rc(8, 1000)
# mavutil.mavlink.ROVER_MODE_HOLD:
@ -762,20 +737,9 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.wait_mode("HOLD")
self.set_rc(8, 1700) # PWM for mode5
self.wait_mode("ACRO")
except Exception as e:
self.print_exception_caught(e)
ex = e
self.context_pop()
if ex is not None:
raise ex
def AuxModeSwitch(self):
'''Set modes via auxswitches'''
self.context_push()
ex = None
try:
# from mavproxy_rc.py
mapping = [0, 1165, 1295, 1425, 1555, 1685, 1815]
self.set_parameter("MODE1", 1) # acro
@ -806,14 +770,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.set_rc(10, 1000) # this re-polls the mode switch
self.wait_mode("ACRO")
self.set_rc(9, 1000)
except Exception as e:
self.print_exception_caught(e)
ex = e
self.context_pop()
if ex is not None:
raise ex
def RCOverridesCancel(self):
'''Test RC overrides Cancel'''
@ -888,10 +844,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
def RCOverrides(self):
'''Test RC overrides'''
self.context_push()
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
ex = None
try:
self.set_parameter("RC12_OPTION", 46)
self.reboot_sitl()
@ -1119,29 +1072,18 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.end_subtest("Checking higher-channel semantics")
except Exception as e:
self.print_exception_caught(e)
ex = e
self.disarm_vehicle()
self.context_pop()
self.reboot_sitl()
if ex is not None:
raise ex
def MANUAL_CONTROL(self):
'''Test mavlink MANUAL_CONTROL'''
self.context_push()
self.set_parameter("SYSID_MYGCS", self.mav.source_system)
ex = None
try:
self.set_parameter("RC12_OPTION", 46) # enable/disable rc overrides
self.set_parameters({
"SYSID_MYGCS": self.mav.source_system,
"RC12_OPTION": 46, # enable/disable rc overrides
})
self.reboot_sitl()
self.change_mode("MANUAL")
self.wait_ready_to_arm()
self.zero_throttle()
self.arm_vehicle()
self.progress("start moving forward a little")
normal_rc_throttle = 1700
@ -1209,16 +1151,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.progress("Waiting for RC to revert to normal RC input")
self.wait_rc_channel_value(3, normal_rc_throttle, timeout=10)
except Exception as e:
self.print_exception_caught(e)
ex = e
self.disarm_vehicle()
self.context_pop()
self.reboot_sitl()
if ex is not None:
raise ex
def CameraMission(self):
'''Test Camera Mission Items'''
@ -4880,9 +4813,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.stop_mavproxy(mavproxy)
# self.load_fence("rover-path-planning-fence.txt")
self.load_mission("rover-path-planning-mission.txt")
self.context_push()
ex = None
try:
self.set_parameters({
"AVOID_ENABLE": 3,
"OA_TYPE": 2,
@ -4901,14 +4831,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
# mission has RTL as last item
self.wait_distance_to_home(3, 7, timeout=300)
self.disarm_vehicle()
except Exception as e:
self.disarm_vehicle(force=True)
self.print_exception_caught(e)
ex = e
self.context_pop()
self.reboot_sitl()
if ex is not None:
raise ex
def send_guided_mission_item(self, loc, target_system=1, target_component=1):
self.mav.mav.mission_item_send(
@ -4930,9 +4852,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
def test_poly_fence_object_avoidance_guided_pathfinding(self, target_system=1, target_component=1):
self.load_fence("rover-path-planning-fence.txt")
self.context_push()
ex = None
try:
self.set_parameters({
"AVOID_ENABLE": 3,
"OA_TYPE": 2,
@ -4943,8 +4862,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.wait_ready_to_arm()
self.arm_vehicle()
self.set_parameter("FENCE_ENABLE", 1)
if self.mavproxy is not None:
self.mavproxy.send("fence list\n")
target_loc = mavutil.location(40.073800, -105.229172)
self.send_guided_mission_item(target_loc,
target_system=target_system,
@ -4952,13 +4869,6 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
self.wait_location(target_loc, timeout=300)
self.do_RTL(timeout=300)
self.disarm_vehicle()
except Exception as e:
self.print_exception_caught(e)
ex = e
self.context_pop()
self.reboot_sitl()
if ex is not None:
raise ex
def WheelEncoders(self):
'''make sure wheel encoders are generally working'''