GCS_MAVLink: send mission item requests to correct destination

The correct destination is the GCS which last set the mission count,
not the last GCS that requested it!
This commit is contained in:
Peter Barker 2017-10-11 12:16:20 +11:00 committed by Andrew Tridgell
parent 2b4cf54797
commit bb2573f945
1 changed files with 3 additions and 2 deletions

View File

@ -356,8 +356,6 @@ void GCS_MAVLINK::handle_mission_request_list(AP_Mission &mission, mavlink_messa
// set variables to help handle the expected sending of commands to the GCS
waypoint_receiving = false; // record that we are sending commands (i.e. not receiving)
waypoint_dest_sysid = msg->sysid; // record system id of GCS who has requested the commands
waypoint_dest_compid = msg->compid; // record component id of GCS who has requested the commands
}
/*
@ -510,6 +508,9 @@ void GCS_MAVLINK::handle_mission_count(AP_Mission &mission, mavlink_message_t *m
waypoint_request_i = 0; // reset the next expected command number to zero
waypoint_request_last = packet.count; // record how many commands we expect to receive
waypoint_timelast_request = 0; // set time we last requested commands to zero
waypoint_dest_sysid = msg->sysid; // record system id of GCS who wants to upload the mission
waypoint_dest_compid = msg->compid; // record component id of GCS who wants to upload the mission
}
/*