diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 58bad8867e..d2b97762df 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -44,7 +44,7 @@ class AutoTestRover(AutoTest): def is_rover(self): return True - def get_rudder_channel(self): + def get_stick_arming_channel(self): return int(self.get_parameter("RCMAP_ROLL")) ########################################################## diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index b4d1fc788d..50695d9863 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -73,7 +73,7 @@ class AutoTestCopter(AutoTest): def is_copter(self): return True - def get_rudder_channel(self): + def get_stick_arming_channel(self): return int(self.get_parameter("RCMAP_YAW")) def get_disarm_delay(self): diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index dd6e72e314..1cf256d7e7 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -47,7 +47,7 @@ class AutoTestPlane(AutoTest): def is_plane(self): return True - def get_rudder_channel(self): + def get_stick_arming_channel(self): return int(self.get_parameter("RCMAP_YAW")) def get_disarm_delay(self): diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 2a4bba1781..767f5885e4 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -813,7 +813,7 @@ class AutoTest(ABC): out_trim = int(self.get_parameter("RC%u_TRIM" % chan)) self.set_rc(chan, out_trim) - def get_rudder_channel(self): + def get_stick_arming_channel(self): """Return the Rudder channel number as set in parameter.""" raise ErrorException("Rudder parameter is not supported by vehicle %s frame %s", (self.vehicleinfo_key(), self.frame)) @@ -903,38 +903,38 @@ class AutoTest(ABC): def arm_motors_with_rc_input(self, timeout=20): """Arm motors with radio.""" self.progress("Arm motors with radio") - self.set_output_to_max(self.get_rudder_channel()) + self.set_output_to_max(self.get_stick_arming_channel()) tstart = self.get_sim_time() while True: self.wait_heartbeat() tdelta = self.get_sim_time_cached() - tstart if self.mav.motors_armed(): self.progress("MOTORS ARMED OK WITH RADIO") - self.set_output_to_trim(self.get_rudder_channel()) + self.set_output_to_trim(self.get_stick_arming_channel()) self.progress("Arm in %ss" % tdelta) # TODO check arming time return True print("Not armed after %f seconds" % (tdelta)) if tdelta > timeout: break self.progress("Failed to ARM with radio") - self.set_output_to_trim(self.get_rudder_channel()) + self.set_output_to_trim(self.get_stick_arming_channel()) return False def disarm_motors_with_rc_input(self, timeout=20): """Disarm motors with radio.""" self.progress("Disarm motors with radio") - self.set_output_to_min(self.get_rudder_channel()) + self.set_output_to_min(self.get_stick_arming_channel()) tstart = self.get_sim_time() while self.get_sim_time_cached() < tstart + timeout: self.wait_heartbeat() if not self.mav.motors_armed(): disarm_delay = self.get_sim_time_cached() - tstart self.progress("MOTORS DISARMED OK WITH RADIO") - self.set_output_to_trim(self.get_rudder_channel()) + self.set_output_to_trim(self.get_stick_arming_channel()) self.progress("Disarm in %ss" % disarm_delay) # TODO check disarming time return True self.progress("Failed to DISARM with radio") - self.set_output_to_trim(self.get_rudder_channel()) + self.set_output_to_trim(self.get_stick_arming_channel()) return False def arm_motors_with_switch(self, switch_chan, timeout=20): diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 07c286b72e..17e90d4557 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -46,7 +46,7 @@ class AutoTestQuadPlane(AutoTest): def is_plane(self): return True - def get_rudder_channel(self): + def get_stick_arming_channel(self): return int(self.get_parameter("RCMAP_YAW")) def get_disarm_delay(self):