Skip to content

Commit

Permalink
autotest: test for fence margin warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Dec 11, 2024
1 parent 6655158 commit ce3674f
Showing 1 changed file with 73 additions and 0 deletions.
73 changes: 73 additions & 0 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -1905,6 +1905,78 @@ def FenceFloorAutoEnableOnArming(self):
# Disable the fence using mavlink command to ensure cleaned up SITL state
self.assert_fence_disabled()

def FenceMargin(self, timeout=180):
'''Test warning on crossing fence margin'''
# enable fence, disable avoidance
self.set_parameters({
"FENCE_ENABLE": 1,
"FENCE_TYPE": 2,
"FENCE_MARGIN" : 20,
"AVOID_ENABLE": 0,
"FENCE_OPTIONS": 4
})

self.change_mode("LOITER")
self.wait_ready_to_arm()

# fence requires home to be set:
m = self.poll_home_position(quiet=False)

self.takeoff(10, mode="LOITER")

# first east
self.progress("turn east")
self.set_rc(4, 1580)
self.wait_heading(160, timeout=60)
self.set_rc(4, 1500)

fence_radius = self.get_parameter("FENCE_RADIUS")

self.progress("flying forward (east) until we hit fence")
pitching_forward = True
self.set_rc(2, 1100)

self.progress("Waiting for fence breach")
tstart = self.get_sim_time()
while not self.mode_is("RTL"):
if self.get_sim_time_cached() - tstart > 30:
raise NotAchievedException("Did not breach fence")

m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
alt = m.relative_alt / 1000.0 # mm -> m
home_distance = self.distance_to_home(use_cached_home=True)
self.progress("Alt: %.02f HomeDistance: %.02f (fence radius=%f)" %
(alt, home_distance, fence_radius))

self.progress("Waiting until we get home and disarm")
tstart = self.get_sim_time()
while self.get_sim_time_cached() < tstart + timeout:
m = self.mav.recv_match(type='GLOBAL_POSITION_INT', blocking=True)
alt = m.relative_alt / 1000.0 # mm -> m
home_distance = self.distance_to_home(use_cached_home=True)
self.progress("Alt: %.02f HomeDistance: %.02f" %
(alt, home_distance))
# recenter pitch sticks once we're home so we don't fly off again
if pitching_forward and home_distance < 50:
pitching_forward = False
self.set_rc(2, 1475)
# disable fence
self.set_parameter("FENCE_ENABLE", 0)
if (alt <= 1 and home_distance < 10) or (not self.armed() and home_distance < 10):
# reduce throttle
self.zero_throttle()
self.change_mode("LAND")
self.wait_landed_and_disarmed()
self.progress("Reached home OK")
self.zero_throttle()
return

# give we're testing RTL, doing one here probably doesn't make sense
home_distance = self.distance_to_home(use_cached_home=True)
raise AutoTestTimeoutException(
"Fence test failed to reach home (%fm distance) - "
"timed out after %u seconds" % (home_distance, timeout,))

def GPSGlitchLoiter(self, timeout=30, max_distance=20):
"""fly_gps_glitch_loiter_test. Fly south east in loiter and test
reaction to gps glitch."""
Expand Down Expand Up @@ -10808,6 +10880,7 @@ def tests1d(self):
self.FenceFloorEnabledLanding,
self.FenceFloorAutoDisableLanding,
self.FenceFloorAutoEnableOnArming,
self.FenceMargin,
self.AutoTuneSwitch,
self.GPSGlitchLoiter,
self.GPSGlitchLoiter2,
Expand Down

0 comments on commit ce3674f

Please sign in to comment.