Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Correct fence handling in fieldcheck #1399

Merged
merged 2 commits into from
Jun 10, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
43 changes: 32 additions & 11 deletions MAVProxy/modules/mavproxy_fieldcheck/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,7 @@ def check_parameters(self, fix=False):

if self.vehicle_type == mavutil.mavlink.MAV_TYPE_FIXED_WING:
want_values["FENCE_ACTION"] = 1 # RTL
want_values["RTL_AUTOLAND"] = 2 # go directly to landing sequence
elif self.vehicle_type == mavutil.mavlink.MAV_TYPE_QUADROTOR:
want_values["FENCE_ACTION"] = 4 # Brake or RTL

Expand Down Expand Up @@ -170,19 +171,39 @@ def check_fence_location(self):
fencemod.cmd_list(None)
return False

count = fencemod.count()
if count < 6:
self.whinge("Too few fence points")
return False
ret = True
for i in range(fencemod.fenceloader.count()):
p = fencemod.fenceloader.point(i)
loc = mavutil.location(p.lat, p.lng)
global fencepoints_good
global count

fencepoints_good = True
count = 0

def fencepoint_checker(offset, p):
global fencepoints_good
global count
if isinstance(p, mavutil.mavlink.MAVLink_mission_item_message):
lat = p.x
lng = p.y
elif isinstance(p, mavutil.mavlink.MAVLink_mission_item_int_message):
lat = p.x * 1e-7
lng = p.y * 1e-7
else:
raise TypeError(f"What's a {type(p)}?")
loc = mavutil.location(lat, lng)
dist = self.get_distance(self.location, loc)
if dist > self.fc_settings.fence_maxdist:
self.whinge("Fencepoint %i too far away (%fm)" % (i, dist))
ret = False
return ret
if fencepoints_good:
self.whinge("Fencepoint %i too far away (%fm)" % (offset, dist))
fencepoints_good = False
count += 1

fencemod.apply_function_to_points(fencepoint_checker)

min_fence_points = 6
if count < min_fence_points:
self.whinge(f"Too few fence points; {count} < {min_fence_points}")
return False

return fencepoints_good

def check_rally(self):
rallymod = self.module('rally')
Expand Down
Loading