From 3963290e9fd95e6ea042ee87a2d39af2104ef258 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 19 Jan 2024 12:32:06 +0000 Subject: [PATCH] autotest: add copter tests for auto-enable fence options --- Tools/autotest/arducopter.py | 48 ++++++++++++++++++++++++++++++++++-- 1 file changed, 46 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 35ba20e26fcefe..975cfc09436b7b 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1734,6 +1734,50 @@ def FenceFloorAutoDisableLanding(self): self.do_fence_disable() self.assert_fence_disabled() + def FenceFloorAutoEnableOnArming(self): + """Ensures we can auto-enable fences on arming and still takeoff and land""" + + fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE + + self.set_parameters({ + "AVOID_ENABLE": 0, + "FENCE_TYPE": 11, + "FENCE_ALT_MIN": 10, + "FENCE_ALT_MAX": 20, + "FENCE_AUTOENABLE" : 3, + }) + + self.change_mode("GUIDED") + # Check fence is not enabled + self.assert_fence_disabled() + + self.wait_ready_to_arm() + self.arm_vehicle() + self.user_takeoff(alt_min=15) + + # Check fence is enabled + 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(0) + # the breach should have cleared since we auto-disable the + # fence on landing + self.assert_fence_disabled() + + # Assert fences have gone now that we have landed and disarmed + self.assert_sensor_state(fence_bit, present=True, enabled=False) + + # Disable the fence using mavlink command to ensure cleaned up SITL state + 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.""" @@ -7455,7 +7499,7 @@ def AvoidanceAltFence(self): self.set_rc(3, 1080) tstart = self.get_sim_time() while True: - if self.get_sim_time_cached() - tstart > 120: + if self.get_sim_time_cached() - tstart > 20: break alt = self.get_altitude(relative=True) self.progress("Altitude %s" % alt) @@ -7471,7 +7515,6 @@ def AvoidanceAltFence(self): if ex is not None: raise ex - def global_position_int_for_location(self, loc, time_boot, heading=0): return self.mav.mav.global_position_int_encode( int(time_boot * 1000), # time_boot_ms @@ -10226,6 +10269,7 @@ def tests1d(self): self.MinAltFence, self.FenceFloorEnabledLanding, self.FenceFloorAutoDisableLanding, + self.FenceFloorAutoEnableOnArming, self.AutoTuneSwitch, self.GPSGlitchLoiter, self.GPSGlitchLoiter2,