diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index eb84112528..be66a04478 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -1124,9 +1124,12 @@ class AutoTestPlane(vehicle_test_suite.TestSuite): def TestRCRelay(self): '''Test Relay RC Channel Option''' - self.set_parameter("RC12_OPTION", 28) # Relay On/Off + self.set_parameters({ + "RELAY1_FUNCTION": 1, # Enable relay as a standard relay pin + "RC12_OPTION": 28 # Relay On/Off + }) self.set_rc(12, 1000) - self.reboot_sitl() # needed for RC12_OPTION to take effect + self.reboot_sitl() # needed for RC12_OPTION and RELAY1_FUNCTION to take effect off = self.get_parameter("SIM_PIN_MASK") if off: diff --git a/Tools/autotest/default_params/rover.parm b/Tools/autotest/default_params/rover.parm index 9095f40720..58e064d81b 100644 --- a/Tools/autotest/default_params/rover.parm +++ b/Tools/autotest/default_params/rover.parm @@ -24,8 +24,8 @@ RC1_MAX 2000 RC1_MIN 1000 RC3_MAX 2000 RC3_MIN 1000 -RELAY_PIN 1 -RELAY_PIN2 2 +RELAY1_PIN 1 +RELAY2_PIN 2 SERVO1_MIN 1000 SERVO1_MAX 2000 SERVO3_MAX 2000 diff --git a/Tools/autotest/default_params/vee-gull 005.param b/Tools/autotest/default_params/vee-gull 005.param index 2ae334ae8b..6e5143632d 100644 --- a/Tools/autotest/default_params/vee-gull 005.param +++ b/Tools/autotest/default_params/vee-gull 005.param @@ -456,10 +456,7 @@ RCMAP_ROLL,1 RCMAP_THROTTLE,3 RCMAP_YAW,4 RELAY_DEFAULT,0 -RELAY_PIN,13 -RELAY_PIN2,-1 -RELAY_PIN3,-1 -RELAY_PIN4,-1 +RELAY1_PIN,13 RLL_RATE_D,0.000000 RLL_RATE_FF,0.255000 RLL_RATE_I,0.050000 diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 2f0870b351..8df6779667 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -568,6 +568,13 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) '''Test ServoRelayEvents''' for method in self.run_cmd, self.run_cmd_int: self.context_push() + + self.set_parameters({ + "RELAY1_FUNCTION": 1, # Enable relay 1 as a standard relay pin + "RELAY2_FUNCTION": 1, # Enable relay 2 as a standard relay pin + }) + self.reboot_sitl() # Needed for relay functions to take effect + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0) off = self.get_parameter("SIM_PIN_MASK") method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1) @@ -602,8 +609,14 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) "on": 0, }) - # add another servo: - self.set_parameter("RELAY_PIN6", 14) + # add another relay and ensure that it changes the "present field" + self.set_parameters({ + "RELAY6_FUNCTION": 1, # Enable relay 6 as a standard relay pin + "RELAY6_PIN": 14, # Set pin number + }) + self.reboot_sitl() # Needed for relay function to take effect + self.set_message_rate_hz("RELAY_STATUS", 10) # Need to re-request the message since reboot + self.assert_received_message_field_values('RELAY_STATUS', { "present": 35, "on": 0, @@ -5352,7 +5365,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.context_collect("STATUSTEXT") self.set_parameters({ "SCR_ENABLE": 1, - "RELAY_PIN": 1, + "RELAY1_FUNCTION": 1, + "RELAY1_PIN": 1 }) self.install_example_script_context("RCIN_test.lua") self.reboot_sitl()