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

mavwp: remove old fences-in-waypoints code #984

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
27 changes: 0 additions & 27 deletions mavwp.py
Original file line number Diff line number Diff line change
Expand Up @@ -289,10 +289,6 @@ def view_indexes(self, done=None):
break
idx += 1

exclusion_start = -1
exclusion_count = -1
inclusion_start = -1
inclusion_count = -1
while idx < self.count():
w = self.wp(idx)
if idx in done:
Expand All @@ -306,35 +302,12 @@ def view_indexes(self, done=None):
if self.is_location_wp(w):
ret.append(idx)
continue
# display loops for exclusion and inclusion zones
if w.command == mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION:
if exclusion_start == -1:
exclusion_count = int(w.param1)
exclusion_start = idx
if idx == exclusion_start + exclusion_count - 1:
ret.append(idx)
ret.append(exclusion_start)
return ret
if w.command == mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION:
if inclusion_start == -1:
inclusion_count = int(w.param1)
inclusion_start = idx
if idx == inclusion_start + inclusion_count - 1:
ret.append(idx)
ret.append(inclusion_start)
return ret
if self.is_location_wp(w):
ret.append(idx)
if w.command in [ mavutil.mavlink.MAV_CMD_NAV_LAND,
mavutil.mavlink.MAV_CMD_NAV_VTOL_LAND ]:
# stop at landing points
return ret
exc_zones = [mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION,
mavutil.mavlink.MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION]
w2 = self.wp(idx+1)
if w2 is not None and w.command not in exc_zones and w2.command in exc_zones:
# don't draw a line from last WP to first exc zone
return ret
idx += 1
return ret

Expand Down
Loading