Skip to content

Commit 3486ae9

Browse files
committed
mavproxy_wp: add option to reset mission counters when setting waypoint
e.g "wp set 2 reset"
1 parent a9577e8 commit 3486ae9

File tree

1 file changed

+16
-3
lines changed

1 file changed

+16
-3
lines changed

Diff for: MAVProxy/modules/mavproxy_wp.py

+16-3
Original file line numberDiff line numberDiff line change
@@ -307,8 +307,15 @@ def cmd_editor(self, args):
307307
self.mpstate.functions.process_stdin("module load misseditor", immediate=True)
308308

309309
def cmd_set(self, args):
310-
if len(args) != 1:
311-
print("usage: wp set <wpindex>")
310+
usage = "usage: wp set <wpindex> [reset]"
311+
reset = False
312+
if len(args) == 2:
313+
if args[1] != "reset":
314+
print(usage)
315+
return
316+
reset = True
317+
elif len(args) != 1:
318+
print(usage)
312319
return
313320

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

326333
if self.settings.wp_use_waypoint_set_current or supports is False:
334+
if reset:
335+
print("Reset unavailable, wp command NOT executed")
336+
return
327337
self.master.waypoint_set_current_send(wp_num)
328338
else:
339+
p2 = 0
340+
if reset:
341+
p2 = 1
329342
self.master.mav.command_long_send(
330343
self.target_system,
331344
self.target_component,
332345
mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT,
333346
0,
334-
wp_num, 0, 0, 0, 0, 0, 0
347+
wp_num, p2, 0, 0, 0, 0, 0
335348
)
336349

337350
def cmd_add(self, args):

0 commit comments

Comments
 (0)