Allow mission jump counters to be reset without changing waypoint#32722
Merged
peterbarker merged 4 commits intoArduPilot:masterfrom Apr 15, 2026
Merged
Conversation
- fixes integer truncation bugs which would have param1=INT16+1 load seq=1 - adds support for passing in -1 as the index number meaning don't-change seq but may allow for resetting the mission state We would cast uint32_t(-1) into a uint16_t when passing into is_valid_index....
tridge
reviewed
Apr 14, 2026
| const uint32_t seq = (uint32_t)packet.param1; | ||
| if (!mission->is_valid_index(seq)) { | ||
| return MAV_RESULT_FAILED; | ||
| if (packet.param1 >= 0) { |
Contributor
|
can be merged with the -1 check |
so if value -2 is supplied it gets DENIED
e8e83ef to
8a50dcc
Compare
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Add this suggestion to a batch that can be applied as a single commit.This suggestion is invalid because no changes were made to the code.Suggestions cannot be applied while the pull request is closed.Suggestions cannot be applied while viewing a subset of changes.Only one suggestion per line can be applied in a batch.Add this suggestion to a batch that can be applied as a single commit.Applying suggestions on deleted lines is not supported.You must change the existing code in this line in order to create a valid suggestion.Outdated suggestions cannot be applied.This suggestion has been applied or marked resolved.Suggestions cannot be applied from pending reviews.Suggestions cannot be applied on multi-line comments.Suggestions cannot be applied while the pull request is queued to merge.Suggestion cannot be applied right now. Please check back later.
Summary
Allows resetting the jump counters without resetting the current waypoint.
Classification & Testing (check all that apply and add your own)
Description
Previously it wasn't possible to reset the jump counters without also setting the waypoint, meaning you're stuck with a race condition.
This understands new meanings given in the mavlink message where "-1" for your waypoint number means "ignore".
ArduPilot MAVLink PR is here: ArduPilot/mavlink#498