-
Notifications
You must be signed in to change notification settings - Fork 13.7k
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
mavlink: support mission transfer cancellation #14139
Conversation
This adds support for MAV_MISSION_OPERATION_CANCELLED which can be used to cancel an ongoing upload or download of mission/geofence/rally items.
Looks fine to me, but an additional review from someone more intimately familiar with the current mission manager would be good. |
_time_last_recv = hrt_absolute_time(); | ||
|
||
if (_transfer_seq == current_item_count()) { | ||
if (wpa.type == MAV_MISSION_ACCEPTED && _transfer_seq == current_item_count()) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This is probably minor, but I'm wondering if there's any benefit in separately handling the mission_ack type check and the mission sync state (eg _transfer_seq).
For example if wpa.type isn't MAV_MISSION_ACCEPTED
or MAV_MISSION_OPERATION_CANCELLED
do we want to handle that error separately (debug logging) and also stop the transfer (_transfer_in_progress = false
).
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
We are eventually logging all cases in the else
below. Generally, I try to look into these cases when they happen one by one.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This is really minor, but isn't the message we send to the ground (send_statustext_critical) on failure now potentially wrong? The transfer could finish (all items) and if the client populated the wrong MAV_MISSION_RESULT we'd send a bogus error.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Agreed, if a GCS sends a NACK, we should not send an error.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Ok, I removed the send_statustext_critical
in 0141ab3.
_time_last_recv = hrt_absolute_time(); | ||
|
||
if (_transfer_seq == current_item_count()) { | ||
if (wpa.type == MAV_MISSION_ACCEPTED && _transfer_seq == current_item_count()) { |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Agreed, if a GCS sends a NACK, we should not send an error.
PX4_DEBUG("WPM: MISSION_ACK OK all items sent, switch to state IDLE"); | ||
|
||
} else if (wpa.type == MAV_MISSION_OPERATION_CANCELLED) { | ||
PX4_DEBUG("WPM: MISSION_ACK CANCELLED, switch to state IDLE"); | ||
_transfer_in_progress = false; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This is only set for mission uploads, whereas here we land only on downloads, so you don't need to reset it here.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
You're right but that's not obvious from the name.
Removed in dd505a9.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
You remove the wrong one.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Stupid me, thanks. ff23988
If the GCS decided something is a NACK it should have already shown whatever the error is. The autopilot does not need to repeat it.
_transfer_in_progress is only used for uploads, so we don't need to reset it here.
This adds support for MAV_MISSION_OPERATION_CANCELLED which can be used
to cancel an ongoing upload or download of mission/geofence/rally items.
Tested in SITL against MAVSDK integration test:
As added in: mavlink/mavlink#1044