mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
GCS_MAVLink: send mission item requests to correct destination for partial updates
The correct destination is the GCS which last requested to update the mission (full or partial), not just the last GCS to set the mission count (full only).
This commit is contained in:
parent
33be8de1f3
commit
ec5faed133
@ -556,6 +556,9 @@ void GCS_MAVLINK::handle_mission_write_partial_list(AP_Mission &mission, mavlink
|
||||
waypoint_receiving = true;
|
||||
waypoint_request_i = packet.start_index;
|
||||
waypoint_request_last= packet.end_index;
|
||||
|
||||
waypoint_dest_sysid = msg->sysid; // record system id of GCS who wants to partially update the mission
|
||||
waypoint_dest_compid = msg->compid; // record component id of GCS who wants to partially update the mission
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user