Skip to content

Commit

Permalink
mavproxy_wp: skip DO_LAND_START waypoints when splitting
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Oct 17, 2024
1 parent 2e2a701 commit d6f3089
Showing 1 changed file with 18 additions and 12 deletions.
30 changes: 18 additions & 12 deletions MAVProxy/modules/mavproxy_wp.py
Original file line number Diff line number Diff line change
Expand Up @@ -556,18 +556,24 @@ def cmd_split(self, args):
print("wp is not a location command")
return

prev = num - 1
if prev < 1 or prev > self.wploader.count():
print("Bad item %u" % num)
return
prev_wp = self.wploader.wp(prev)
if prev_wp is None:
print("Could not get previous wp %u" % prev)
return
prev_loc = self.get_loc(prev_wp)
if prev_loc is None:
print("previous wp is not a location command")
return
prev = num
while True:
prev = prev - 1
if prev < 1 or prev > self.wploader.count():
print("Bad item %u" % num)
return
prev_wp = self.wploader.wp(prev)
if prev_wp is None:
print("Could not get previous wp %u" % prev)
return
if prev_wp.command == mavutil.mavlink.MAV_CMD_DO_LAND_START:
print("skipping DLS {prev}")
continue
prev_loc = self.get_loc(prev_wp)
if prev_loc is None:
print("previous wp is not a location command")
return
break

if wp.frame != prev_wp.frame:
print("waypoints differ in frame (%u vs %u)" %
Expand Down

0 comments on commit d6f3089

Please sign in to comment.