From 9c212c10f4e962839a7b4708aa67aa8d83700d32 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 13 Jan 2024 18:03:42 +0000 Subject: [PATCH] autotest: clean-up fence manipulation functions and add test for auto-enablement on copter --- Tools/autotest/arducopter.py | 13 +++++++------ Tools/autotest/vehicle_test_suite.py | 21 ++++++++------------- 2 files changed, 15 insertions(+), 19 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 00ba7fae2160c1..6d09ec47b766f0 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1687,15 +1687,14 @@ def FenceFloorEnabledLanding(self): self.assert_fence_disabled() def FenceFloorAutoDisableLanding(self): - """Ensures we can initiate and complete an RTL while the fence is - enabled. - """ + """Ensures we can initiate and complete an RTL while the fence is enabled""" + fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE self.progress("Test Landing while fence floor enabled") self.set_parameters({ "AVOID_ENABLE": 0, - "FENCE_TYPE": 15, + "FENCE_TYPE": 11, "FENCE_ALT_MIN": 10, "FENCE_ALT_MAX": 20, "FENCE_AUTOENABLE" : 1, @@ -1707,7 +1706,7 @@ def FenceFloorAutoDisableLanding(self): self.user_takeoff(alt_min=15) # Check fence is enabled - self.do_fence_enable() + self.do_fence_enable_except_floor() self.assert_fence_enabled() # Change to RC controlled mode @@ -1719,7 +1718,9 @@ def FenceFloorAutoDisableLanding(self): # Assert fence is not healthy now that we are in RTL self.assert_sensor_state(fence_bit, healthy=False) - self.wait_landed_and_disarmed() + self.wait_landed_and_disarmed(0) + # the breach should have cleared since we auto-disable the + # fence on landing self.assert_fence_enabled() # Assert fence is healthy now that we have landed disarmed diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index be0cecc95fee4b..eed66bbdb766c3 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -6592,22 +6592,17 @@ def do_set_relay_mavproxy(self, relay_num, on_off): self.mavproxy.expect("Loaded module relay") self.mavproxy.send("relay set %d %d\n" % (relay_num, on_off)) - def do_fence_en_or_dis_able(self, value, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): - if value: - p1 = 1 - else: - p1 = 0 - self.run_cmd( - mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, - p1=p1, # param1 - want_result=want_result, - ) - def do_fence_enable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): - self.do_fence_en_or_dis_able(True, want_result=want_result) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, want_result=want_result) def do_fence_disable(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): - self.do_fence_en_or_dis_able(False, want_result=want_result) + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, want_result=want_result) + + def do_fence_disable_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0, p2=8, want_result=want_result) + + def do_fence_enable_except_floor(self, want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED): + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=1, p2=7, want_result=want_result) ################################################# # WAIT UTILITIES