Commit f69b38e4 authored by Don Gagne's avatar Don Gagne

Convert to pack/encode_chan apis

parent e7979fd9
......@@ -211,7 +211,7 @@ int APMFirmwarePlugin::manualControlReservedButtonCount(void)
return -1;
}
void APMFirmwarePlugin::_handleParamValue(Vehicle* vehicle, mavlink_message_t* message)
void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle* vehicle, mavlink_message_t* message)
{
Q_UNUSED(vehicle);
......@@ -301,7 +301,7 @@ void APMFirmwarePlugin::_handleOutgoingParamSet(Vehicle* vehicle, LinkInterface*
mavlink_msg_param_set_encode_chan(message->sysid, message->compid, outgoingLink->mavlinkChannel(), message, &paramSet);
}
bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* message)
bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message)
{
QString messageText;
......@@ -410,7 +410,7 @@ bool APMFirmwarePlugin::_handleStatusText(Vehicle* vehicle, mavlink_message_t* m
return true;
}
void APMFirmwarePlugin::_handleHeartbeat(Vehicle* vehicle, mavlink_message_t* message)
void APMFirmwarePlugin::_handleIncomingHeartbeat(Vehicle* vehicle, mavlink_message_t* message)
{
bool flying = false;
......@@ -439,12 +439,12 @@ bool APMFirmwarePlugin::adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_m
switch (message->msgid) {
case MAVLINK_MSG_ID_PARAM_VALUE:
_handleParamValue(vehicle, message);
_handleIncomingParamValue(vehicle, message);
break;
case MAVLINK_MSG_ID_STATUSTEXT:
return _handleStatusText(vehicle, message);
return _handleIncomingStatusText(vehicle, message);
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartbeat(vehicle, message);
_handleIncomingHeartbeat(vehicle, message);
break;
}
......
......@@ -114,10 +114,10 @@ private:
static bool _isTextSeverityAdjustmentNeeded(const APMFirmwareVersion& firmwareVersion);
void _setInfoSeverity(mavlink_message_t* message) const;
QString _getMessageText(mavlink_message_t* message) const;
void _handleParamValue(Vehicle* vehicle, mavlink_message_t* message);
void _handleIncomingParamValue(Vehicle* vehicle, mavlink_message_t* message);
bool _handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message);
void _handleIncomingHeartbeat(Vehicle* vehicle, mavlink_message_t* message);
void _handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message);
bool _handleStatusText(Vehicle* vehicle, mavlink_message_t* message);
void _handleHeartbeat(Vehicle* vehicle, mavlink_message_t* message);
void _soloVideoHandshake(Vehicle* vehicle);
bool _textSeverityAdjustmentNeeded;
......
This diff is collapsed.
......@@ -365,13 +365,14 @@ void MockLinkFileServer::_sendResponse(uint8_t targetSystemId, uint8_t targetCom
request->hdr.seqNumber = seqNumber;
mavlink_msg_file_transfer_protocol_pack(_systemIdServer, // System ID
0, // Component ID
&mavlinkMessage, // Mavlink Message to pack into
0, // Target network
targetSystemId,
targetComponentId,
(uint8_t*)request); // Payload
mavlink_msg_file_transfer_protocol_pack_chan(_systemIdServer, // System ID
0, // Component ID
_mockLink->mavlinkChannel(),
&mavlinkMessage, // Mavlink Message to pack into
0, // Target network
targetSystemId,
targetComponentId,
(uint8_t*)request); // Payload
_mockLink->respondWithMavlinkMessage(mavlinkMessage);
}
......
......@@ -96,12 +96,13 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
mavlink_message_t responseMsg;
mavlink_msg_mission_count_pack(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
msg.compid, // Target is original sender
itemCount); // Number of mission items
mavlink_msg_mission_count_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
_mockLink->mavlinkChannel(),
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
msg.compid, // Target is original sender
itemCount); // Number of mission items
_mockLink->respondWithMavlinkMessage(responseMsg);
} else {
qCDebug(MockLinkMissionItemHandlerLog) << "_handleMissionRequestList not responding due to failure mode";
......@@ -149,18 +150,19 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
item = _missionItems[request.seq];
}
mavlink_msg_mission_item_pack(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
msg.compid, // Target is original sender
request.seq, // Index of mission item being sent
item.frame,
item.command,
item.current,
item.autocontinue,
item.param1, item.param2, item.param3, item.param4,
item.x, item.y, item.z);
mavlink_msg_mission_item_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
_mockLink->mavlinkChannel(),
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
msg.compid, // Target is original sender
request.seq, // Index of mission item being sent
item.frame,
item.command,
item.current,
item.autocontinue,
item.param1, item.param2, item.param3, item.param4,
item.x, item.y, item.z);
_mockLink->respondWithMavlinkMessage(responseMsg);
}
}
......@@ -218,7 +220,11 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
missionRequest.target_component = _mavlinkProtocol->getComponentId();
missionRequest.seq = sequenceNumber;
mavlink_msg_mission_request_encode(_mockLink->vehicleId(), MAV_COMP_ID_MISSIONPLANNER, &message, &missionRequest);
mavlink_msg_mission_request_encode_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
_mockLink->mavlinkChannel(),
&message,
&missionRequest);
_mockLink->respondWithMavlinkMessage(message);
// If response with Mission Item doesn't come before timer fires it's an error
......@@ -238,7 +244,11 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
missionAck.target_component = _mavlinkProtocol->getComponentId();
missionAck.type = ackType;
mavlink_msg_mission_ack_encode(_mockLink->vehicleId(), MAV_COMP_ID_MISSIONPLANNER, &message, &missionAck);
mavlink_msg_mission_ack_encode_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
_mockLink->mavlinkChannel(),
&message,
&missionAck);
_mockLink->respondWithMavlinkMessage(message);
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment