1 #ifndef MAVLINKPROTOBUFMANAGER_HPP
2 #define MAVLINKPROTOBUFMANAGER_HPP
5 #include <google/protobuf/message.h>
11 #include <mavlink_types.h>
12 #include <pixhawk/pixhawk.pb.h>
21 : mRegisteredTypeCount(0)
24 , kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN)
25 , kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN)
29 std::tr1::shared_ptr<px::GLOverlay> msg(
new px::GLOverlay);
35 std::tr1::shared_ptr<px::ObstacleList> msg(
new px::ObstacleList);
41 std::tr1::shared_ptr<px::ObstacleMap> msg(
new px::ObstacleMap);
47 std::tr1::shared_ptr<px::Path> msg(
new px::Path);
53 std::tr1::shared_ptr<px::PointCloudXYZI> msg(
new px::PointCloudXYZI);
59 std::tr1::shared_ptr<px::PointCloudXYZRGB> msg(
new px::PointCloudXYZRGB);
65 std::tr1::shared_ptr<px::RGBDImage> msg(
new px::RGBDImage);
70 mStreamID = rand() + 1;
73 bool fragmentMessage(uint8_t system_id, uint8_t component_id,
74 uint8_t target_system, uint8_t target_component,
75 const google::protobuf::Message& protobuf_msg,
76 std::vector<mavlink_extended_message_t>& fragments)
const
78 TypeMap::const_iterator it = mTypeMap.find(protobuf_msg.GetTypeName());
79 if (it == mTypeMap.end())
81 std::cout <<
"# WARNING: Protobuf message with type "
82 << protobuf_msg.GetTypeName() <<
" is not registered."
87 uint8_t typecode = it->second;
89 std::string data = protobuf_msg.SerializeAsString();
91 int fragmentCount = (protobuf_msg.ByteSize() + kExtendedPayloadMaxSize - 1) / kExtendedPayloadMaxSize;
92 unsigned int offset = 0;
94 for (
int i = 0; i < fragmentCount; ++i)
96 mavlink_extended_message_t fragment;
99 uint8_t* payload =
reinterpret_cast<uint8_t*
>(fragment.base_msg.payload64);
100 unsigned int length = 0;
103 if (i < fragmentCount - 1)
105 length = kExtendedPayloadMaxSize;
110 length = protobuf_msg.ByteSize() - kExtendedPayloadMaxSize * (fragmentCount - 1);
113 memcpy(payload, &target_system, 1);
114 memcpy(payload + 1, &target_component, 1);
115 memcpy(payload + 2, &typecode, 1);
116 memcpy(payload + 3, &length, 4);
117 memcpy(payload + 7, &mStreamID, 2);
118 memcpy(payload + 9, &offset, 4);
119 memcpy(payload + 13, &flags, 1);
121 fragment.base_msg.msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
122 mavlink_finalize_message(&fragment.base_msg, system_id, component_id, kExtendedHeaderSize, 0);
125 fragment.extended_payload_len = length;
126 memcpy(fragment.extended_payload, &data[offset], length);
128 fragments.push_back(fragment);
134 std::cerr <<
"# INFO: Split extended message with size "
135 << protobuf_msg.ByteSize() <<
" into "
136 << fragmentCount <<
" fragments." << std::endl;
142 bool cacheFragment(mavlink_extended_message_t& msg)
144 if (!validFragment(msg))
148 std::cerr <<
"# WARNING: Message is not a valid fragment. "
149 <<
"Dropping message..." << std::endl;
155 uint8_t* payload =
reinterpret_cast<uint8_t*
>(msg.base_msg.payload64);
156 uint8_t typecode = 0;
157 unsigned int length = 0;
158 unsigned short streamID = 0;
159 unsigned int offset = 0;
162 memcpy(&typecode, payload + 2, 1);
163 memcpy(&length, payload + 3, 4);
164 memcpy(&streamID, payload + 7, 2);
165 memcpy(&offset, payload + 9, 4);
166 memcpy(&flags, payload + 13, 1);
168 if (typecode >= mTypeMap.size())
170 std::cout <<
"# WARNING: Protobuf message with type code "
171 <<
static_cast<int>(typecode) <<
" is not registered." << std::endl;
175 bool reassemble =
false;
177 FragmentQueue::iterator it = mFragmentQueue.find(streamID);
178 if (it == mFragmentQueue.end())
182 mFragmentQueue[streamID].push_back(msg);
184 if ((flags & 0x1) != 0x1)
191 std::cerr <<
"# INFO: Added fragment to new queue."
199 std::cerr <<
"# WARNING: Message is not a valid fragment. "
200 <<
"Dropping message..." << std::endl;
206 std::deque<mavlink_extended_message_t>& queue = it->second;
212 queue.push_back(msg);
214 if ((flags & 0x1) != 0x1)
223 std::cerr <<
"# WARNING: Message is not a valid fragment. "
224 <<
"Dropping message..." << std::endl;
230 if (fragmentDataSize(queue.back()) + fragmentOffset(queue.back()) != offset)
234 std::cerr <<
"# WARNING: Previous fragment(s) have been lost. "
235 <<
"Dropping message and clearing queue..." << std::endl;
241 queue.push_back(msg);
243 if ((flags & 0x1) != 0x1)
253 std::deque<mavlink_extended_message_t>& queue = mFragmentQueue[streamID];
256 for (
size_t i = 0; i < queue.size(); ++i)
258 mavlink_extended_message_t& mavlink_msg = queue.at(i);
260 data.append(reinterpret_cast<char*>(&mavlink_msg.extended_payload[0]),
261 static_cast<size_t>(mavlink_msg.extended_payload_len));
264 mMessages.at(typecode)->ParseFromString(data);
266 mMessageAvailable.at(typecode) =
true;
272 std::cerr <<
"# INFO: Reassembled fragments for message with typename "
273 << mMessages.at(typecode)->GetTypeName() <<
" and size "
274 << mMessages.at(typecode)->ByteSize()
282 bool getMessage(std::tr1::shared_ptr<google::protobuf::Message>& msg)
284 for (
size_t i = 0; i < mMessageAvailable.size(); ++i)
286 if (mMessageAvailable.at(i))
288 msg = mMessages.at(i);
289 mMessageAvailable.at(i) =
false;
299 void registerType(
const std::tr1::shared_ptr<google::protobuf::Message>& msg)
301 mTypeMap[msg->GetTypeName()] = mRegisteredTypeCount;
302 ++mRegisteredTypeCount;
303 mMessages.push_back(msg);
304 mMessageAvailable.push_back(
false);
307 bool validFragment(
const mavlink_extended_message_t& msg)
const
309 if (msg.base_msg.magic != MAVLINK_STX ||
310 msg.base_msg.len != kExtendedHeaderSize ||
311 msg.base_msg.msgid != MAVLINK_MSG_ID_EXTENDED_MESSAGE)
317 checksum = crc_calculate(reinterpret_cast<const uint8_t*>(&msg.base_msg.len), MAVLINK_CORE_HEADER_LEN);
318 crc_accumulate_buffer(&checksum, reinterpret_cast<const char*>(&msg.base_msg.payload64), kExtendedHeaderSize);
319 #if MAVLINK_CRC_EXTRA
320 static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
321 crc_accumulate(mavlink_message_crcs[msg.base_msg.msgid], &checksum);
324 if (mavlink_ck_a(&(msg.base_msg)) != (uint8_t)(checksum & 0xFF) &&
325 mavlink_ck_b(&(msg.base_msg)) != (uint8_t)(checksum >> 8))
333 unsigned int fragmentDataSize(
const mavlink_extended_message_t& msg)
const
335 const uint8_t* payload =
reinterpret_cast<const uint8_t*
>(msg.base_msg.payload64);
337 return *(
reinterpret_cast<const unsigned int*
>(payload + 3));
340 unsigned int fragmentOffset(
const mavlink_extended_message_t& msg)
const
342 const uint8_t* payload =
reinterpret_cast<const uint8_t*
>(msg.base_msg.payload64);
344 return *(
reinterpret_cast<const unsigned int*
>(payload + 9));
347 int mRegisteredTypeCount;
348 unsigned short mStreamID;
351 typedef std::map<std::string, uint8_t> TypeMap;
353 std::vector< std::tr1::shared_ptr<google::protobuf::Message> > mMessages;
354 std::vector<bool> mMessageAvailable;
356 typedef std::map<unsigned short, std::deque<mavlink_extended_message_t> > FragmentQueue;
357 FragmentQueue mFragmentQueue;
359 const int kExtendedHeaderSize;
372 const int kExtendedPayloadMaxSize;
MAVLink comm protocol built from common.xml.
Definition: mavlink_protobuf_manager.hpp:17
Definition: mavlink_protobuf_manager.hpp:14