From a76eb8e5087c23518b74f7c0b3fa1ae6a11f763c Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 22 Dec 2023 09:36:34 +0000 Subject: [PATCH] autotest: add test for auto-disabling min alt fence breaches on disarming --- Tools/autotest/arducopter.py | 47 +++++++++++++++++++++++++++++++++++- 1 file changed, 46 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 991f088098d9c5..879f47541f3de3 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1675,16 +1675,60 @@ def FenceFloorEnabledLanding(self): self.set_rc(3, 1800) self.wait_mode('RTL', timeout=120) + self.wait_landed_and_disarmed() self.assert_fence_enabled() - # Assert fence is not healthy + # Assert fence is healthy now that we have landed disarmed self.assert_sensor_state(fence_bit, healthy=False) # Disable the fence using mavlink command to ensure cleaned up SITL state self.do_fence_disable() self.assert_fence_disabled() + def FenceFloorAutoDisableLanding(self): + """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_ALT_MIN": 10, + "FENCE_ALT_MAX": 20, + "FENCE_OPTIONS" : 4, + }) + + self.change_mode("GUIDED") + self.wait_ready_to_arm() + self.arm_vehicle() + self.user_takeoff(alt_min=15) + + # Check fence is enabled + self.do_fence_enable() + self.assert_fence_enabled() + + # Change to RC controlled mode + self.change_mode('LOITER') + + self.set_rc(3, 1800) + + self.wait_mode('RTL', timeout=120) + # 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.assert_fence_enabled() + + # Assert fence is healthy now that we have landed disarmed + self.assert_sensor_state(fence_bit, healthy=True) + + # Disable the fence using mavlink command to ensure cleaned up SITL state + self.do_fence_disable() + self.assert_fence_disabled() + def GPSGlitchLoiter(self, timeout=30, max_distance=20): """fly_gps_glitch_loiter_test. Fly south east in loiter and test reaction to gps glitch.""" @@ -10056,6 +10100,7 @@ def tests1d(self): self.MaxAltFence, self.MinAltFence, self.FenceFloorEnabledLanding, + self.FenceFloorAutoDisableLanding, self.AutoTuneSwitch, self.GPSGlitchLoiter, self.GPSGlitchLoiter2,