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

mavproxy_wp: skip DO_LAND_START waypoints when splitting #1475

Merged
merged 1 commit into from
Nov 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
29 changes: 17 additions & 12 deletions MAVProxy/modules/mavproxy_wp.py
Original file line number Diff line number Diff line change
Expand Up @@ -556,18 +556,23 @@ 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:
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