Skip to content

Commit

Permalink
mavproxy_wp: add option to reset mission counters when setting waypoint
Browse files Browse the repository at this point in the history
e.g "wp set 2 reset"
  • Loading branch information
peterbarker committed Oct 2, 2024
1 parent 10fa60f commit fb5a482
Showing 1 changed file with 16 additions and 3 deletions.
19 changes: 16 additions & 3 deletions MAVProxy/modules/mavproxy_wp.py
Original file line number Diff line number Diff line change
Expand Up @@ -307,8 +307,15 @@ def cmd_editor(self, args):
self.mpstate.functions.process_stdin("module load misseditor", immediate=True)

def cmd_set(self, args):
if len(args) != 1:
print("usage: wp set <wpindex>")
usage = "usage: wp set <wpindex> [reset]"
reset = False
if len(args) == 2:
if args[1] != "reset":
print(usage)
return
reset = True
elif len(args) != 1:
print(usage)
return

wp_num = int(args[0])
Expand All @@ -324,14 +331,20 @@ def cmd_set(self, args):
# we "know" because we hook receipt of COMMAND_ACK.

if self.settings.wp_use_waypoint_set_current or supports is False:
if reset:
print("Reset unavailable, wp command NOT executed")
return
self.master.waypoint_set_current_send(wp_num)
else:
p2 = 0
if reset:
p2 = 1
self.master.mav.command_long_send(
self.target_system,
self.target_component,
mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
0,
wp_num, 0, 0, 0, 0, 0, 0
wp_num, p2, 0, 0, 0, 0, 0
)

def cmd_add(self, args):
Expand Down

0 comments on commit fb5a482

Please sign in to comment.