diff --git a/src/mavsdk/core/mavlink_mission_transfer_client.cpp b/src/mavsdk/core/mavlink_mission_transfer_client.cpp index bca0c55e41..56a8a5e060 100644 --- a/src/mavsdk/core/mavlink_mission_transfer_client.cpp +++ b/src/mavsdk/core/mavlink_mission_transfer_client.cpp @@ -339,7 +339,6 @@ void MavlinkMissionTransferClient::UploadWorkItem::process_mission_request( std::lock_guard lock(_mutex); // We only support int, so we nack this and thus tell the autopilot to use int. - UNUSED(request_message); if (!_sender.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { mavlink_message_t message; @@ -348,8 +347,8 @@ void MavlinkMissionTransferClient::UploadWorkItem::process_mission_request( mavlink_address.component_id, channel, &message, - request.target_system, - request.target_component, + request_message.sysid, + request_message.compid, MAV_MISSION_UNSUPPORTED, _type); return message; diff --git a/src/mavsdk/core/mavlink_mission_transfer_client_test.cpp b/src/mavsdk/core/mavlink_mission_transfer_client_test.cpp index 15cf478ae0..6885a074eb 100644 --- a/src/mavsdk/core/mavlink_mission_transfer_client_test.cpp +++ b/src/mavsdk/core/mavlink_mission_transfer_client_test.cpp @@ -904,11 +904,11 @@ mavlink_message_t make_mission_request(uint8_t type, int sequence) { mavlink_message_t message; mavlink_msg_mission_request_pack( - own_address.system_id, - own_address.component_id, - &message, target_address.system_id, target_address.component_id, + &message, + own_address.system_id, + own_address.component_id, sequence, type); return message;