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

mavlink: support mission transfer cancellation #14139

Merged
merged 4 commits into from Feb 24, 2020
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
13 changes: 10 additions & 3 deletions src/modules/mavlink/mavlink_mission.cpp
Expand Up @@ -601,14 +601,16 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg)
if (CHECK_SYSID_COMPID_MISSION(wpa)) {
if ((msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid)) {
if (_state == MAVLINK_WPM_STATE_SENDLIST && _mission_type == wpa.mission_type) {

_time_last_recv = hrt_absolute_time();

if (_transfer_seq == current_item_count()) {
if (wpa.type == MAV_MISSION_ACCEPTED && _transfer_seq == current_item_count()) {
Copy link
Member

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).

Copy link
Contributor Author

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.

Copy link
Member

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.

Copy link
Member

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.

Copy link
Contributor Author

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.

PX4_DEBUG("WPM: MISSION_ACK OK all items sent, switch to state IDLE");

} else {
_mavlink->send_statustext_critical("WPM: ERR: not all items sent -> IDLE");
} else if (wpa.type == MAV_MISSION_OPERATION_CANCELLED) {
PX4_DEBUG("WPM: MISSION_ACK CANCELLED, switch to state IDLE");

} else {
PX4_DEBUG("WPM: MISSION_ACK ERROR: not all items sent, switch to state IDLE anyway");
}

Expand All @@ -628,6 +630,11 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg)
send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
}

} else if (wpa.type == MAV_MISSION_OPERATION_CANCELLED) {
PX4_DEBUG("WPM: MISSION_ACK CANCELLED, switch to state IDLE");
switch_to_idle_state();
_transfer_in_progress = false;

} else if (wpa.type != MAV_MISSION_ACCEPTED) {
PX4_WARN("Mission ack result was %d", wpa.type);
}
Expand Down