diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 08ef17839c..f0105bfc1c 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -7140,6 +7140,50 @@ switch value''' (new_mask, m3.state)) self.progress("correct BUTTON_CHANGE event received") + if self.is_tracker(): + # tracker starts armed, which is annoying + self.progress("Skipping arm/disarm tests for tracker") + return + + self.wait_ready_to_arm() + self.set_parameter("BTN_FUNC%u" % btn, 41) # ARM/DISARM + self.set_parameter("SIM_PIN_MASK", mask) + self.wait_armed() + self.set_parameter("SIM_PIN_MASK", 0) + self.wait_disarmed() + + if self.is_rover(): + self.context_push() + # arming should be inhibited while e-STOP is in use: + # set the function: + self.set_parameter("BTN_FUNC%u" % btn, 31) + # invert the sense of the pin, so eStop is asserted when pin is low: + self.set_parameter("BTN_OPTIONS%u" % btn, 1<<1) + self.reboot_sitl() + # assert the pin: + self.set_parameter("SIM_PIN_MASK", mask) + self.wait_ready_to_arm() + self.arm_vehicle() + self.disarm_vehicle() + # de-assert the pin: + self.set_parameter("SIM_PIN_MASK", 0) + self.delay_sim_time(1) # 5Hz update rate on Button library + self.context_collect("STATUSTEXT") + # try to arm the vehicle: + self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + 1, # ARM + 0, + 0, + 0, + 0, + 0, + 0, + want_result=mavutil.mavlink.MAV_RESULT_FAILED + ) + self.wait_statustext("PreArm: Motors Emergency Stopped", check_context=True) + self.context_pop() + self.reboot_sitl() + def compare_number_percent(self, num1, num2, percent): if num1 == 0 and num2 == 0: return True diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 763316da1d..cce9f7193e 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -4457,7 +4457,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) 0, # p6 - test order (see MOTOR_TEST_ORDER) 0, # p7 ) - self.mav.motors_armed_wait() + self.wait_armed() self.progress("Waiting for magic throttle value") self.wait_servo_channel_value(3, magic_throttle_value) self.wait_servo_channel_value(3, self.get_parameter("RC3_TRIM", 5), timeout=10)