Skip to content

Commit

Permalink
autotest: test for circle exclusion fence using AUTOENABLE=2
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Jul 18, 2024
1 parent 43566e0 commit 8c41369
Showing 1 changed file with 66 additions and 0 deletions.
66 changes: 66 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -3898,6 +3898,71 @@ def FenceAutoEnableDisableSwitch(self):
self.change_altitude(self.homeloc.alt + cruise_alt)
self.fly_home_land_and_disarm(timeout=250)

def FenceCircleExclusionAutoEnable(self):
'''Tests autolanding when alt min fence is enabled'''
self.set_parameters({
"FENCE_TYPE": 2, # Set fence type to circle
"FENCE_ACTION": 1, # Set action to RTL
"FENCE_AUTOENABLE": 2,
"FENCE_ENABLE" : 0,
"RTL_AUTOLAND" : 2,
})

# Grab Home Position
self.mav.recv_match(type='HOME_POSITION', blocking=True)
self.homeloc = self.mav.location()

fence_loc = self.home_position_as_mav_location()
self.location_offset_ne(fence_loc, 50, 50)
radius_exc = 20
item = self.mav.mav.mission_item_int_encode(
1,
1,
0, # seq
mavutil.mavlink.MAV_FRAME_GLOBAL_INT,
mavutil.mavlink.MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION,
0, # current
0, # autocontinue
radius_exc, # p1
0, # p2
0, # p3
0, # p4
int(fence_loc.lat * 1e7), # latitude
int(fence_loc.lng * 1e7), # longitude
0.0000, # altitude
mavutil.mavlink.MAV_MISSION_TYPE_FENCE)

self.upload_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE, [ item ])
self.download_using_mission_protocol(mavutil.mavlink.MAV_MISSION_TYPE_FENCE)

self.wait_ready_to_arm()
self.arm_vehicle()

self.takeoff(alt=50, mode='TAKEOFF')
self.change_mode("FBWA")
self.set_rc(3, 1100) # lower throttle

self.progress("Waiting for RTL")
tstart = self.get_sim_time()
mode = "RTL"
while not self.mode_is(mode, drain_mav=False):
self.mav.messages['HEARTBEAT'].custom_mode
self.progress("mav.flightmode=%s Want=%s Alt=%f" % (
self.mav.flightmode, mode, self.get_altitude(relative=True)))
if (self.get_sim_time_cached() > tstart + 120):
raise WaitModeTimeout("Did not change mode")
self.progress("Got mode %s" % mode)
# switch to FBWA
self.change_mode("FBWA")
self.set_rc(3, 1500) # raise throttle
self.wait_altitude(25, 35, timeout=50, relative=True)
self.set_rc(3, 1000) # lower throttle
# Now check we can land
self.fly_home_land_and_disarm()
self.clear_mission(mavutil.mavlink.MAV_MISSION_TYPE_ALL)
self.set_current_waypoint(0, check_afterwards=False)
self.set_rc(3, 1000) # lower throttle

def FenceEnableDisableSwitch(self):
'''Tests enablement and disablement of fences on a switch'''
fence_bit = mavutil.mavlink.MAV_SYS_STATUS_GEOFENCE
Expand Down Expand Up @@ -5822,6 +5887,7 @@ def tests(self):
self.FenceMinAltEnableAutoland,
self.FenceMinAltAutoEnableAbort,
self.FenceAutoEnableDisableSwitch,
self.FenceCircleExclusionAutoEnable,
self.FenceEnableDisableSwitch,
self.FenceEnableDisableAux,
self.FenceBreachedChangeMode,
Expand Down

0 comments on commit 8c41369

Please sign in to comment.