Browse Source

GCS_MAVLink: On mission_set_current report the requested item if the set was a success

The problem with reporting the mission index, is that the mission index will be walked
forward until its referring to a nav target, which means that if a DO_ command was
requested, the requesting mavlink device had no way to validate the command was
accepted, it would have to make a infrence from it's copy of the mission
master
Michael du Breuil 9 years ago committed by Andrew Tridgell
parent
commit
7a18d59099
  1. 2
      libraries/GCS_MAVLink/GCS_Common.cpp

2
libraries/GCS_MAVLink/GCS_Common.cpp

@ -393,7 +393,7 @@ void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, mavlink_messag @@ -393,7 +393,7 @@ void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, mavlink_messag
// set current command
if (mission.set_current_cmd(packet.seq)) {
mavlink_msg_mission_current_send(chan, mission.get_current_nav_cmd().index);
mavlink_msg_mission_current_send(chan, packet.seq);
}
}

Loading…
Cancel
Save