Browse Source

Us MAV_COMP_ID_AUTOPILOT1 instead of MAV_COMP_ID_MISSIONPLANNER

QGC4.4
Don Gagne 7 years ago
parent
commit
c7b1880c42
  1. 16
      src/MissionManager/PlanManager.cc
  2. 8
      src/comm/MockLinkMissionItemHandler.cc

16
src/MissionManager/PlanManager.cc

@ -114,7 +114,7 @@ void PlanManager::_writeMissionCount(void) @@ -114,7 +114,7 @@ void PlanManager::_writeMissionCount(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_writeMissionItems.count(),
_planType);
@ -157,7 +157,7 @@ void PlanManager::_requestList(void) @@ -157,7 +157,7 @@ void PlanManager::_requestList(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_planType);
_vehicle->sendMessageOnLink(_dedicatedLink, message);
@ -296,7 +296,7 @@ void PlanManager::_readTransactionComplete(void) @@ -296,7 +296,7 @@ void PlanManager::_readTransactionComplete(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
MAV_MISSION_ACCEPTED,
_planType);
@ -354,7 +354,7 @@ void PlanManager::_requestNextMissionItem(void) @@ -354,7 +354,7 @@ void PlanManager::_requestNextMissionItem(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_itemIndicesToRead[0],
_planType);
} else {
@ -363,7 +363,7 @@ void PlanManager::_requestNextMissionItem(void) @@ -363,7 +363,7 @@ void PlanManager::_requestNextMissionItem(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_itemIndicesToRead[0],
_planType);
}
@ -536,7 +536,7 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m @@ -536,7 +536,7 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m
_dedicatedLink->mavlinkChannel(),
&messageOut,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
missionRequest.seq,
item->frame(),
item->command(),
@ -556,7 +556,7 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m @@ -556,7 +556,7 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m
_dedicatedLink->mavlinkChannel(),
&messageOut,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
missionRequest.seq,
item->frame(),
item->command(),
@ -897,7 +897,7 @@ void PlanManager::_removeAllWorker(void) @@ -897,7 +897,7 @@ void PlanManager::_removeAllWorker(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_planType);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
_startAckTimeout(AckMissionClearAll);

8
src/comm/MockLinkMissionItemHandler.cc

@ -156,7 +156,7 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message @@ -156,7 +156,7 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
mavlink_message_t responseMsg;
mavlink_msg_mission_count_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_mockLink->mavlinkChannel(),
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
@ -224,7 +224,7 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t& @@ -224,7 +224,7 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
}
mavlink_msg_mission_item_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_mockLink->mavlinkChannel(),
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
@ -310,7 +310,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber) @@ -310,7 +310,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
mavlink_message_t message;
mavlink_msg_mission_request_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_mockLink->mavlinkChannel(),
&message,
_mavlinkProtocol->getSystemId(),
@ -332,7 +332,7 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType) @@ -332,7 +332,7 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
mavlink_message_t message;
mavlink_msg_mission_ack_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_mockLink->mavlinkChannel(),
&message,
_mavlinkProtocol->getSystemId(),

Loading…
Cancel
Save