From 6fcf85edb838bfe0b5695071de02cc5a0790c886 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 9 Mar 2022 08:15:15 +1100 Subject: [PATCH] autotest: more changes for plane disarm disallow --- Tools/autotest/arduplane.py | 8 ++++---- Tools/autotest/common.py | 18 +++++++++++++++++- Tools/autotest/quadplane.py | 15 +-------------- 3 files changed, 22 insertions(+), 19 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 1668fc401b..570fa365a6 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -1038,7 +1038,7 @@ class AutoTestPlane(AutoTest): "SIM_RC_FAIL": 0, # fix receiver }) self.zero_throttle() - self.disarm_vehicle() + self.disarm_vehicle(force=True) self.context_pop() self.reboot_sitl() @@ -2268,7 +2268,7 @@ function''' self.wait_waypoint(4, 4, timeout=1200, max_dist=120) # Disarm - self.disarm_vehicle() + self.disarm_vehicle_expect_fail() self.progress("Mission OK") @@ -2365,7 +2365,7 @@ function''' raise NotAchievedException("Airspeed did not reduce with lower SOAR_VSPEED") # Disarm - self.disarm_vehicle() + self.disarm_vehicle_expect_fail() self.progress("Mission OK") @@ -2872,7 +2872,7 @@ function''' self.context_clear_collection("STATUSTEXT") ################################################################### - self.disarm_vehicle() + self.disarm_vehicle(force=True) except Exception as e: self.print_exception_caught(e) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index 7efa598cc7..8da34d53dc 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -4361,6 +4361,22 @@ class AutoTest(ABC): timeout=timeout) return self.wait_disarmed() + def disarm_vehicle_expect_fail(self): + '''disarm, checking first that non-forced disarm fails, then doing a forced disarm''' + self.progress("Disarm - 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 - forced") + self.disarm_vehicle(force=True) + def wait_disarmed_default_wait_time(self): return 30 @@ -11191,7 +11207,7 @@ switch value''' # ok done, stop the engine if self.is_plane(): self.zero_throttle() - if not self.disarm_vehicle(): + if not self.disarm_vehicle(force=True): raise NotAchievedException("Failed to DISARM") def test_frsky_d(self): diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 4ede8602c3..923e9b4ed9 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -248,20 +248,7 @@ 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 - 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.disarm_vehicle_expect_fail() self.arm_vehicle() self.progress("Verify that airmode is still on")