From 9dd4685ea09ba008bbcb4fede400d80d9a67e8bd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Mar 2022 08:12:47 +1100 Subject: [PATCH] autotest: adjust for arming change in plane expect disarm to fail when airmode on --- Tools/autotest/quadplane.py | 18 +++++++++++++++--- 1 file changed, 15 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 999689a9ad..4ede8602c3 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -248,13 +248,25 @@ class AutoTestQuadPlane(AutoTest): self.progress("Waiting for Motor1 to speed up") self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge) - self.progress("Disarm/rearm with GCS") - self.disarm_vehicle() + self.progress("Disarm/rearm with GCS - expect to fail") + self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, + 0, # DISARM + 0, + 0, + 0, + 0, + 0, + 0, + timeout=10, + want_result=mavutil.mavlink.MAV_RESULT_FAILED) + + self.progress("Disarm/rearm with GCS - forced") + self.disarm_vehicle(force=True) self.arm_vehicle() self.progress("Verify that airmode is still on") self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge) - self.disarm_vehicle() + self.disarm_vehicle(force=True) self.wait_ready_to_arm() def test_motor_mask(self):