S Morita / mbed-mros2

Dependents:   mbed-os-example-mros2 example-mbed-mros2-sub-pose example-mbed-mros2-pub-twist example-mbed-mros2-mturtle-teleop

Committer:
smoritaemb
Date:
Thu Dec 30 21:06:29 2021 +0900
Revision:
0:580aba13d1a1
Updated to catch up to mros2 v2.3

Who changed what in which revision?

UserRevisionLine numberNew contents of line
smoritaemb 0:580aba13d1a1 1 /*
smoritaemb 0:580aba13d1a1 2 The MIT License
smoritaemb 0:580aba13d1a1 3 Copyright (c) 2019 Lehrstuhl Informatik 11 - RWTH Aachen University
smoritaemb 0:580aba13d1a1 4 Permission is hereby granted, free of charge, to any person obtaining a copy
smoritaemb 0:580aba13d1a1 5 of this software and associated documentation files (the "Software"), to deal
smoritaemb 0:580aba13d1a1 6 in the Software without restriction, including without limitation the rights
smoritaemb 0:580aba13d1a1 7 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
smoritaemb 0:580aba13d1a1 8 copies of the Software, and to permit persons to whom the Software is
smoritaemb 0:580aba13d1a1 9 furnished to do so, subject to the following conditions:
smoritaemb 0:580aba13d1a1 10 The above copyright notice and this permission notice shall be included in
smoritaemb 0:580aba13d1a1 11 all copies or substantial portions of the Software.
smoritaemb 0:580aba13d1a1 12 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
smoritaemb 0:580aba13d1a1 13 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
smoritaemb 0:580aba13d1a1 14 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
smoritaemb 0:580aba13d1a1 15 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
smoritaemb 0:580aba13d1a1 16 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
smoritaemb 0:580aba13d1a1 17 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
smoritaemb 0:580aba13d1a1 18 THE SOFTWARE
smoritaemb 0:580aba13d1a1 19
smoritaemb 0:580aba13d1a1 20 This file is part of embeddedRTPS.
smoritaemb 0:580aba13d1a1 21
smoritaemb 0:580aba13d1a1 22 Author: i11 - Embedded Software, RWTH Aachen University
smoritaemb 0:580aba13d1a1 23 */
smoritaemb 0:580aba13d1a1 24
smoritaemb 0:580aba13d1a1 25 #ifndef RTPS_MESSAGES_H
smoritaemb 0:580aba13d1a1 26 #define RTPS_MESSAGES_H
smoritaemb 0:580aba13d1a1 27
smoritaemb 0:580aba13d1a1 28 #include "rtps/common/types.h"
smoritaemb 0:580aba13d1a1 29
smoritaemb 0:580aba13d1a1 30 #include <array>
smoritaemb 0:580aba13d1a1 31
smoritaemb 0:580aba13d1a1 32 namespace rtps {
smoritaemb 0:580aba13d1a1 33
smoritaemb 0:580aba13d1a1 34 namespace SMElement {
smoritaemb 0:580aba13d1a1 35 // TODO endianess
smoritaemb 0:580aba13d1a1 36 enum ParameterId : uint16_t {
smoritaemb 0:580aba13d1a1 37 PID_PAD = 0x0000,
smoritaemb 0:580aba13d1a1 38 PID_SENTINEL = 0x0001,
smoritaemb 0:580aba13d1a1 39 PID_USER_DATA = 0x002c,
smoritaemb 0:580aba13d1a1 40 PID_TOPIC_NAME = 0x0005,
smoritaemb 0:580aba13d1a1 41 PID_TYPE_NAME = 0x0007,
smoritaemb 0:580aba13d1a1 42 PID_GROUP_DATA = 0x002d,
smoritaemb 0:580aba13d1a1 43 PID_TOPIC_DATA = 0x002e,
smoritaemb 0:580aba13d1a1 44 PID_DURABILITY = 0x001d,
smoritaemb 0:580aba13d1a1 45 PID_DURABILITY_SERVICE = 0x001e,
smoritaemb 0:580aba13d1a1 46 PID_DEADLINE = 0x0023,
smoritaemb 0:580aba13d1a1 47 PID_LATENCY_BUDGET = 0x0027,
smoritaemb 0:580aba13d1a1 48 PID_LIVELINESS = 0x001b,
smoritaemb 0:580aba13d1a1 49 PID_RELIABILITY = 0x001a,
smoritaemb 0:580aba13d1a1 50 PID_LIFESPAN = 0x002b,
smoritaemb 0:580aba13d1a1 51 PID_DESTINATION_ORDER = 0x0025,
smoritaemb 0:580aba13d1a1 52 PID_HISTORY = 0x0040,
smoritaemb 0:580aba13d1a1 53 PID_RESOURCE_LIMITS = 0x0041,
smoritaemb 0:580aba13d1a1 54 PID_OWNERSHIP = 0x001f,
smoritaemb 0:580aba13d1a1 55 PID_OWNERSHIP_STRENGTH = 0x0006,
smoritaemb 0:580aba13d1a1 56 PID_PRESENTATION = 0x0021,
smoritaemb 0:580aba13d1a1 57 PID_PARTITION = 0x0029,
smoritaemb 0:580aba13d1a1 58 PID_TIME_BASED_FILTER = 0x0004,
smoritaemb 0:580aba13d1a1 59 PID_TRANSPORT_PRIORITY = 0x0049,
smoritaemb 0:580aba13d1a1 60 PID_PROTOCOL_VERSION = 0x0015,
smoritaemb 0:580aba13d1a1 61 PID_VENDORID = 0x0016,
smoritaemb 0:580aba13d1a1 62 PID_UNICAST_LOCATOR = 0x002f,
smoritaemb 0:580aba13d1a1 63 PID_MULTICAST_LOCATOR = 0x0030,
smoritaemb 0:580aba13d1a1 64 PID_MULTICAST_IPADDRESS = 0x0011,
smoritaemb 0:580aba13d1a1 65 PID_DEFAULT_UNICAST_LOCATOR = 0x0031,
smoritaemb 0:580aba13d1a1 66 PID_DEFAULT_MULTICAST_LOCATOR = 0x0048,
smoritaemb 0:580aba13d1a1 67 PID_METATRAFFIC_UNICAST_LOCATOR = 0x0032,
smoritaemb 0:580aba13d1a1 68 PID_METATRAFFIC_MULTICAST_LOCATOR = 0x0033,
smoritaemb 0:580aba13d1a1 69 PID_DEFAULT_UNICAST_IPADDRESS = 0x000c,
smoritaemb 0:580aba13d1a1 70 PID_DEFAULT_UNICAST_PORT = 0x000e,
smoritaemb 0:580aba13d1a1 71 PID_METATRAFFIC_UNICAST_IPADDRESS = 0x0045,
smoritaemb 0:580aba13d1a1 72 PID_METATRAFFIC_UNICAST_PORT = 0x000d,
smoritaemb 0:580aba13d1a1 73 PID_METATRAFFIC_MULTICAST_IPADDRESS = 0x000b,
smoritaemb 0:580aba13d1a1 74 PID_METATRAFFIC_MULTICAST_PORT = 0x0046,
smoritaemb 0:580aba13d1a1 75 PID_EXPECTS_INLINE_QOS = 0x0043,
smoritaemb 0:580aba13d1a1 76 PID_PARTICIPANT_MANUAL_LIVELINESS_COUNT = 0x0034,
smoritaemb 0:580aba13d1a1 77 PID_PARTICIPANT_BUILTIN_ENDPOINTS = 0x0044,
smoritaemb 0:580aba13d1a1 78 PID_PARTICIPANT_LEASE_DURATION = 0x0002,
smoritaemb 0:580aba13d1a1 79 PID_CONTENT_FILTER_PROPERTY = 0x0035,
smoritaemb 0:580aba13d1a1 80 PID_PARTICIPANT_GUID = 0x0050,
smoritaemb 0:580aba13d1a1 81 PID_PARTICIPANT_ENTITYID = 0x0051,
smoritaemb 0:580aba13d1a1 82 PID_GROUP_GUID = 0x0052,
smoritaemb 0:580aba13d1a1 83 PID_GROUP_ENTITYID = 0x0053,
smoritaemb 0:580aba13d1a1 84 PID_BUILTIN_ENDPOINT_SET = 0x0058,
smoritaemb 0:580aba13d1a1 85 PID_PROPERTY_LIST = 0x0059,
smoritaemb 0:580aba13d1a1 86 PID_ENDPOINT_GUID = 0x005a,
smoritaemb 0:580aba13d1a1 87 PID_TYPE_MAX_SIZE_SERIALIZED = 0x0060,
smoritaemb 0:580aba13d1a1 88 PID_ENTITY_NAME = 0x0062,
smoritaemb 0:580aba13d1a1 89 PID_KEY_HASH = 0x0070,
smoritaemb 0:580aba13d1a1 90 PID_STATUS_INFO = 0x0071
smoritaemb 0:580aba13d1a1 91 };
smoritaemb 0:580aba13d1a1 92
smoritaemb 0:580aba13d1a1 93 enum BuildInEndpointSet : uint32_t {
smoritaemb 0:580aba13d1a1 94 DISC_BIE_PARTICIPANT_ANNOUNCER = 1 << 0,
smoritaemb 0:580aba13d1a1 95 DISC_BIE_PARTICIPANT_DETECTOR = 1 << 1,
smoritaemb 0:580aba13d1a1 96 DISC_BIE_PUBLICATION_ANNOUNCER = 1 << 2,
smoritaemb 0:580aba13d1a1 97 DISC_BIE_PUBLICATION_DETECTOR = 1 << 3,
smoritaemb 0:580aba13d1a1 98 DISC_BIE_SUBSCRIPTION_ANNOUNCER = 1 << 4,
smoritaemb 0:580aba13d1a1 99 DISC_BIE_SUBSCRIPTION_DETECTOR = 1 << 5,
smoritaemb 0:580aba13d1a1 100
smoritaemb 0:580aba13d1a1 101 DISC_BIE_PARTICIPANT_PROXY_ANNOUNCER = 1 << 6,
smoritaemb 0:580aba13d1a1 102 DISC_BIE_PARTICIPANT_PROXY_DETECTOR = 1 << 7,
smoritaemb 0:580aba13d1a1 103 DISC_BIE_PARTICIPANT_STATE_ANNOUNCER = 1 << 8,
smoritaemb 0:580aba13d1a1 104 DISC_BIE_PARTICIPANT_STATE_DETECTOR = 1 << 9,
smoritaemb 0:580aba13d1a1 105
smoritaemb 0:580aba13d1a1 106 BIE_PARTICIPANT_MESSAGE_DATA_WRITER = 1 << 10,
smoritaemb 0:580aba13d1a1 107 BIE_PARTICIPANT_MESSAGE_DATA_READER = 1 << 11,
smoritaemb 0:580aba13d1a1 108 };
smoritaemb 0:580aba13d1a1 109
smoritaemb 0:580aba13d1a1 110 // TODO endianess
smoritaemb 0:580aba13d1a1 111
smoritaemb 0:580aba13d1a1 112 const std::array<uint8_t, 2> SCHEME_CDR_LE{0x00, 0x01};
smoritaemb 0:580aba13d1a1 113 const std::array<uint8_t, 2> SCHEME_PL_CDR_LE{0x00, 0x03};
smoritaemb 0:580aba13d1a1 114
smoritaemb 0:580aba13d1a1 115 struct ParameterList_t {
smoritaemb 0:580aba13d1a1 116 ParameterId pid;
smoritaemb 0:580aba13d1a1 117 uint16_t length;
smoritaemb 0:580aba13d1a1 118 // Values follow
smoritaemb 0:580aba13d1a1 119 } __attribute__((packed));
smoritaemb 0:580aba13d1a1 120 } // namespace SMElement
smoritaemb 0:580aba13d1a1 121
smoritaemb 0:580aba13d1a1 122 enum class SubmessageKind : uint8_t {
smoritaemb 0:580aba13d1a1 123 PAD = 0x01, /* Pad */
smoritaemb 0:580aba13d1a1 124 ACKNACK = 0x06, /* AckNack */
smoritaemb 0:580aba13d1a1 125 HEARTBEAT = 0x07, /* Heartbeat */
smoritaemb 0:580aba13d1a1 126 GAP = 0x08, /* Gap */
smoritaemb 0:580aba13d1a1 127 INFO_TS = 0x09, /* InfoTimestamp */
smoritaemb 0:580aba13d1a1 128 INFO_SRC = 0x0c, /* InfoSource */
smoritaemb 0:580aba13d1a1 129 INFO_REPLY_IP4 = 0x0d, /* InfoReplyIp4 */
smoritaemb 0:580aba13d1a1 130 INFO_DST = 0x0e, /* InfoDestination */
smoritaemb 0:580aba13d1a1 131 INFO_REPLY = 0x0f, /* InfoReply */
smoritaemb 0:580aba13d1a1 132 NACK_FRAG = 0x12, /* NackFrag */
smoritaemb 0:580aba13d1a1 133 HEARTBEAT_FRAG = 0x13, /* HeartbeatFrag */
smoritaemb 0:580aba13d1a1 134 DATA = 0x15, /* Data */
smoritaemb 0:580aba13d1a1 135 DATA_FRAG = 0x16 /* DataFrag */
smoritaemb 0:580aba13d1a1 136 };
smoritaemb 0:580aba13d1a1 137
smoritaemb 0:580aba13d1a1 138 enum SubMessageFlag : uint8_t {
smoritaemb 0:580aba13d1a1 139 FLAG_ENDIANESS = (1 << 0),
smoritaemb 0:580aba13d1a1 140 FLAG_BIG_ENDIAN = (0 << 0),
smoritaemb 0:580aba13d1a1 141 FLAG_LITTLE_ENDIAN = (1 << 0),
smoritaemb 0:580aba13d1a1 142 FLAG_INVALIDATE = (1 << 1),
smoritaemb 0:580aba13d1a1 143 FLAG_INLINE_QOS = (1 << 1),
smoritaemb 0:580aba13d1a1 144 FLAG_NO_PAYLOAD = (0 << 3 | 0 << 2),
smoritaemb 0:580aba13d1a1 145 FLAG_DATA_PAYLOAD = (0 << 3 | 1 << 2),
smoritaemb 0:580aba13d1a1 146 FLAG_FINAL = (1 << 1),
smoritaemb 0:580aba13d1a1 147 FLAG_HB_LIVELINESS = (1 << 2)
smoritaemb 0:580aba13d1a1 148 };
smoritaemb 0:580aba13d1a1 149
smoritaemb 0:580aba13d1a1 150 const std::array<uint8_t, 4> RTPS_PROTOCOL_NAME = {'R', 'T', 'P', 'S'};
smoritaemb 0:580aba13d1a1 151 struct Header {
smoritaemb 0:580aba13d1a1 152 std::array<uint8_t, 4> protocolName;
smoritaemb 0:580aba13d1a1 153 ProtocolVersion_t protocolVersion;
smoritaemb 0:580aba13d1a1 154 VendorId_t vendorId;
smoritaemb 0:580aba13d1a1 155 GuidPrefix_t guidPrefix;
smoritaemb 0:580aba13d1a1 156 static constexpr uint16_t getRawSize() {
smoritaemb 0:580aba13d1a1 157 return sizeof(std::array<uint8_t, 4>) + sizeof(ProtocolVersion_t) +
smoritaemb 0:580aba13d1a1 158 sizeof(VendorId_t) + sizeof(GuidPrefix_t);
smoritaemb 0:580aba13d1a1 159 }
smoritaemb 0:580aba13d1a1 160 };
smoritaemb 0:580aba13d1a1 161
smoritaemb 0:580aba13d1a1 162 struct SubmessageHeader {
smoritaemb 0:580aba13d1a1 163 SubmessageKind submessageId;
smoritaemb 0:580aba13d1a1 164 uint8_t flags;
smoritaemb 0:580aba13d1a1 165 uint16_t submessageLength;
smoritaemb 0:580aba13d1a1 166 static constexpr uint16_t getRawSize() {
smoritaemb 0:580aba13d1a1 167 return sizeof(SubmessageKind) + sizeof(uint8_t) + sizeof(uint16_t);
smoritaemb 0:580aba13d1a1 168 }
smoritaemb 0:580aba13d1a1 169 };
smoritaemb 0:580aba13d1a1 170
smoritaemb 0:580aba13d1a1 171 struct SubmessageData {
smoritaemb 0:580aba13d1a1 172 SubmessageHeader header;
smoritaemb 0:580aba13d1a1 173 uint16_t extraFlags;
smoritaemb 0:580aba13d1a1 174 uint16_t octetsToInlineQos;
smoritaemb 0:580aba13d1a1 175 EntityId_t readerId;
smoritaemb 0:580aba13d1a1 176 EntityId_t writerId;
smoritaemb 0:580aba13d1a1 177 SequenceNumber_t writerSN;
smoritaemb 0:580aba13d1a1 178 static constexpr uint16_t getRawSize() {
smoritaemb 0:580aba13d1a1 179 return SubmessageHeader::getRawSize() + sizeof(uint16_t) +
smoritaemb 0:580aba13d1a1 180 sizeof(uint16_t) + (2 * 3 + 2 * 1) // EntityID
smoritaemb 0:580aba13d1a1 181 + sizeof(SequenceNumber_t);
smoritaemb 0:580aba13d1a1 182 }
smoritaemb 0:580aba13d1a1 183 };
smoritaemb 0:580aba13d1a1 184
smoritaemb 0:580aba13d1a1 185 struct SubmessageHeartbeat {
smoritaemb 0:580aba13d1a1 186 SubmessageHeader header;
smoritaemb 0:580aba13d1a1 187 EntityId_t readerId;
smoritaemb 0:580aba13d1a1 188 EntityId_t writerId;
smoritaemb 0:580aba13d1a1 189 SequenceNumber_t firstSN;
smoritaemb 0:580aba13d1a1 190 SequenceNumber_t lastSN;
smoritaemb 0:580aba13d1a1 191 Count_t count;
smoritaemb 0:580aba13d1a1 192 static constexpr uint16_t getRawSize() {
smoritaemb 0:580aba13d1a1 193 return SubmessageHeader::getRawSize() + (2 * 3 + 2 * 1) // EntityID
smoritaemb 0:580aba13d1a1 194 + 2 * sizeof(SequenceNumber_t) + sizeof(Count_t);
smoritaemb 0:580aba13d1a1 195 }
smoritaemb 0:580aba13d1a1 196 };
smoritaemb 0:580aba13d1a1 197
smoritaemb 0:580aba13d1a1 198 struct SubmessageAckNack {
smoritaemb 0:580aba13d1a1 199 SubmessageHeader header;
smoritaemb 0:580aba13d1a1 200 EntityId_t readerId;
smoritaemb 0:580aba13d1a1 201 EntityId_t writerId;
smoritaemb 0:580aba13d1a1 202 SequenceNumberSet readerSNState;
smoritaemb 0:580aba13d1a1 203 Count_t count;
smoritaemb 0:580aba13d1a1 204 static uint16_t getRawSize(const SequenceNumberSet &set) {
smoritaemb 0:580aba13d1a1 205 uint16_t bitMapSize = 0;
smoritaemb 0:580aba13d1a1 206 if (set.numBits != 0) {
smoritaemb 0:580aba13d1a1 207 bitMapSize = 4 * ((set.numBits / 32) + 1);
smoritaemb 0:580aba13d1a1 208 }
smoritaemb 0:580aba13d1a1 209 return getRawSizeWithoutSNSet() + sizeof(SequenceNumber_t) +
smoritaemb 0:580aba13d1a1 210 sizeof(uint32_t) + bitMapSize; // SequenceNumberSet
smoritaemb 0:580aba13d1a1 211 }
smoritaemb 0:580aba13d1a1 212 static uint16_t getRawSizeWithoutSNSet() {
smoritaemb 0:580aba13d1a1 213 return SubmessageHeader::getRawSize() + (2 * 3 + 2 * 1) // EntityID
smoritaemb 0:580aba13d1a1 214 + sizeof(Count_t);
smoritaemb 0:580aba13d1a1 215 }
smoritaemb 0:580aba13d1a1 216 };
smoritaemb 0:580aba13d1a1 217
smoritaemb 0:580aba13d1a1 218 template <typename Buffer>
smoritaemb 0:580aba13d1a1 219 bool serializeMessage(Buffer &buffer, Header &header) {
smoritaemb 0:580aba13d1a1 220 if (!buffer.reserve(Header::getRawSize())) {
smoritaemb 0:580aba13d1a1 221 return false;
smoritaemb 0:580aba13d1a1 222 }
smoritaemb 0:580aba13d1a1 223
smoritaemb 0:580aba13d1a1 224 buffer.append(header.protocolName.data(), sizeof(std::array<uint8_t, 4>));
smoritaemb 0:580aba13d1a1 225 buffer.append(reinterpret_cast<uint8_t *>(&header.protocolVersion),
smoritaemb 0:580aba13d1a1 226 sizeof(ProtocolVersion_t));
smoritaemb 0:580aba13d1a1 227 buffer.append(header.vendorId.vendorId.data(), sizeof(VendorId_t));
smoritaemb 0:580aba13d1a1 228 buffer.append(header.guidPrefix.id.data(), sizeof(GuidPrefix_t));
smoritaemb 0:580aba13d1a1 229 return true;
smoritaemb 0:580aba13d1a1 230 }
smoritaemb 0:580aba13d1a1 231
smoritaemb 0:580aba13d1a1 232 template <typename Buffer>
smoritaemb 0:580aba13d1a1 233 bool serializeMessage(Buffer &buffer, SubmessageHeader &header) {
smoritaemb 0:580aba13d1a1 234 if (!buffer.reserve(Header::getRawSize())) {
smoritaemb 0:580aba13d1a1 235 return false;
smoritaemb 0:580aba13d1a1 236 }
smoritaemb 0:580aba13d1a1 237 buffer.reserve(SubmessageHeader::getRawSize());
smoritaemb 0:580aba13d1a1 238
smoritaemb 0:580aba13d1a1 239 buffer.append(reinterpret_cast<uint8_t *>(&header.submessageId),
smoritaemb 0:580aba13d1a1 240 sizeof(SubmessageKind));
smoritaemb 0:580aba13d1a1 241 buffer.append(&header.flags, sizeof(uint8_t));
smoritaemb 0:580aba13d1a1 242 buffer.append(reinterpret_cast<uint8_t *>(&header.submessageLength),
smoritaemb 0:580aba13d1a1 243 sizeof(uint16_t));
smoritaemb 0:580aba13d1a1 244 return true;
smoritaemb 0:580aba13d1a1 245 }
smoritaemb 0:580aba13d1a1 246
smoritaemb 0:580aba13d1a1 247 template <typename Buffer>
smoritaemb 0:580aba13d1a1 248 bool serializeMessage(Buffer &buffer, SubmessageData &msg) {
smoritaemb 0:580aba13d1a1 249 if (!buffer.reserve(SubmessageData::getRawSize())) {
smoritaemb 0:580aba13d1a1 250 return false;
smoritaemb 0:580aba13d1a1 251 }
smoritaemb 0:580aba13d1a1 252
smoritaemb 0:580aba13d1a1 253 serializeMessage(buffer, msg.header);
smoritaemb 0:580aba13d1a1 254
smoritaemb 0:580aba13d1a1 255 buffer.append(reinterpret_cast<uint8_t *>(&msg.extraFlags), sizeof(uint16_t));
smoritaemb 0:580aba13d1a1 256 buffer.append(reinterpret_cast<uint8_t *>(&msg.octetsToInlineQos),
smoritaemb 0:580aba13d1a1 257 sizeof(uint16_t));
smoritaemb 0:580aba13d1a1 258 buffer.append(msg.readerId.entityKey.data(), msg.readerId.entityKey.size());
smoritaemb 0:580aba13d1a1 259 buffer.append(reinterpret_cast<uint8_t *>(&msg.readerId.entityKind),
smoritaemb 0:580aba13d1a1 260 sizeof(EntityKind_t));
smoritaemb 0:580aba13d1a1 261 buffer.append(msg.writerId.entityKey.data(), msg.writerId.entityKey.size());
smoritaemb 0:580aba13d1a1 262 buffer.append(reinterpret_cast<uint8_t *>(&msg.writerId.entityKind),
smoritaemb 0:580aba13d1a1 263 sizeof(EntityKind_t));
smoritaemb 0:580aba13d1a1 264 buffer.append(reinterpret_cast<uint8_t *>(&msg.writerSN.high),
smoritaemb 0:580aba13d1a1 265 sizeof(msg.writerSN.high));
smoritaemb 0:580aba13d1a1 266 buffer.append(reinterpret_cast<uint8_t *>(&msg.writerSN.low),
smoritaemb 0:580aba13d1a1 267 sizeof(msg.writerSN.low));
smoritaemb 0:580aba13d1a1 268 return true;
smoritaemb 0:580aba13d1a1 269 }
smoritaemb 0:580aba13d1a1 270
smoritaemb 0:580aba13d1a1 271 template <typename Buffer>
smoritaemb 0:580aba13d1a1 272 bool serializeMessage(Buffer &buffer, SubmessageHeartbeat &msg) {
smoritaemb 0:580aba13d1a1 273 if (!buffer.reserve(SubmessageHeartbeat::getRawSize())) {
smoritaemb 0:580aba13d1a1 274 return false;
smoritaemb 0:580aba13d1a1 275 }
smoritaemb 0:580aba13d1a1 276
smoritaemb 0:580aba13d1a1 277 serializeMessage(buffer, msg.header);
smoritaemb 0:580aba13d1a1 278
smoritaemb 0:580aba13d1a1 279 buffer.append(msg.readerId.entityKey.data(), msg.readerId.entityKey.size());
smoritaemb 0:580aba13d1a1 280 buffer.append(reinterpret_cast<uint8_t *>(&msg.readerId.entityKind),
smoritaemb 0:580aba13d1a1 281 sizeof(EntityKind_t));
smoritaemb 0:580aba13d1a1 282 buffer.append(msg.writerId.entityKey.data(), msg.writerId.entityKey.size());
smoritaemb 0:580aba13d1a1 283 buffer.append(reinterpret_cast<uint8_t *>(&msg.writerId.entityKind),
smoritaemb 0:580aba13d1a1 284 sizeof(EntityKind_t));
smoritaemb 0:580aba13d1a1 285 buffer.append(reinterpret_cast<uint8_t *>(&msg.firstSN.high),
smoritaemb 0:580aba13d1a1 286 sizeof(msg.firstSN.high));
smoritaemb 0:580aba13d1a1 287 buffer.append(reinterpret_cast<uint8_t *>(&msg.firstSN.low),
smoritaemb 0:580aba13d1a1 288 sizeof(msg.firstSN.low));
smoritaemb 0:580aba13d1a1 289 buffer.append(reinterpret_cast<uint8_t *>(&msg.lastSN.high),
smoritaemb 0:580aba13d1a1 290 sizeof(msg.lastSN.high));
smoritaemb 0:580aba13d1a1 291 buffer.append(reinterpret_cast<uint8_t *>(&msg.lastSN.low),
smoritaemb 0:580aba13d1a1 292 sizeof(msg.lastSN.low));
smoritaemb 0:580aba13d1a1 293 buffer.append(reinterpret_cast<uint8_t *>(&msg.count.value),
smoritaemb 0:580aba13d1a1 294 sizeof(msg.count.value));
smoritaemb 0:580aba13d1a1 295 return true;
smoritaemb 0:580aba13d1a1 296 }
smoritaemb 0:580aba13d1a1 297
smoritaemb 0:580aba13d1a1 298 template <typename Buffer>
smoritaemb 0:580aba13d1a1 299 bool serializeMessage(Buffer &buffer, SubmessageAckNack &msg) {
smoritaemb 0:580aba13d1a1 300 if (!buffer.reserve(SubmessageAckNack::getRawSize(msg.readerSNState))) {
smoritaemb 0:580aba13d1a1 301 return false;
smoritaemb 0:580aba13d1a1 302 }
smoritaemb 0:580aba13d1a1 303
smoritaemb 0:580aba13d1a1 304 serializeMessage(buffer, msg.header);
smoritaemb 0:580aba13d1a1 305
smoritaemb 0:580aba13d1a1 306 buffer.append(msg.readerId.entityKey.data(), msg.readerId.entityKey.size());
smoritaemb 0:580aba13d1a1 307 buffer.append(reinterpret_cast<uint8_t *>(&msg.readerId.entityKind),
smoritaemb 0:580aba13d1a1 308 sizeof(EntityKind_t));
smoritaemb 0:580aba13d1a1 309 buffer.append(msg.writerId.entityKey.data(), msg.writerId.entityKey.size());
smoritaemb 0:580aba13d1a1 310 buffer.append(reinterpret_cast<uint8_t *>(&msg.writerId.entityKind),
smoritaemb 0:580aba13d1a1 311 sizeof(EntityKind_t));
smoritaemb 0:580aba13d1a1 312 buffer.append(reinterpret_cast<uint8_t *>(&msg.readerSNState.base.high),
smoritaemb 0:580aba13d1a1 313 sizeof(msg.readerSNState.base.high));
smoritaemb 0:580aba13d1a1 314 buffer.append(reinterpret_cast<uint8_t *>(&msg.readerSNState.base.low),
smoritaemb 0:580aba13d1a1 315 sizeof(msg.readerSNState.base.low));
smoritaemb 0:580aba13d1a1 316 buffer.append(reinterpret_cast<uint8_t *>(&msg.readerSNState.numBits),
smoritaemb 0:580aba13d1a1 317 sizeof(uint32_t));
smoritaemb 0:580aba13d1a1 318 if (msg.readerSNState.numBits != 0) {
smoritaemb 0:580aba13d1a1 319 buffer.append(reinterpret_cast<uint8_t *>(msg.readerSNState.bitMap.data()),
smoritaemb 0:580aba13d1a1 320 4 * ((msg.readerSNState.numBits / 32) + 1));
smoritaemb 0:580aba13d1a1 321 }
smoritaemb 0:580aba13d1a1 322 buffer.append(reinterpret_cast<uint8_t *>(&msg.count.value),
smoritaemb 0:580aba13d1a1 323 sizeof(msg.count.value));
smoritaemb 0:580aba13d1a1 324 return true;
smoritaemb 0:580aba13d1a1 325 }
smoritaemb 0:580aba13d1a1 326
smoritaemb 0:580aba13d1a1 327 struct MessageProcessingInfo {
smoritaemb 0:580aba13d1a1 328 MessageProcessingInfo(const uint8_t *data, DataSize_t size)
smoritaemb 0:580aba13d1a1 329 : data(data), size(size) {}
smoritaemb 0:580aba13d1a1 330 const uint8_t *data;
smoritaemb 0:580aba13d1a1 331 const DataSize_t size;
smoritaemb 0:580aba13d1a1 332
smoritaemb 0:580aba13d1a1 333 //! Offset to the next unprocessed byte
smoritaemb 0:580aba13d1a1 334 DataSize_t nextPos = 0;
smoritaemb 0:580aba13d1a1 335
smoritaemb 0:580aba13d1a1 336 inline const uint8_t *getPointerToCurrentPos() const {
smoritaemb 0:580aba13d1a1 337 return &data[nextPos];
smoritaemb 0:580aba13d1a1 338 }
smoritaemb 0:580aba13d1a1 339
smoritaemb 0:580aba13d1a1 340 //! Returns the size of data which isn't processed yet
smoritaemb 0:580aba13d1a1 341 inline DataSize_t getRemainingSize() const { return size - nextPos; }
smoritaemb 0:580aba13d1a1 342 };
smoritaemb 0:580aba13d1a1 343
smoritaemb 0:580aba13d1a1 344 bool deserializeMessage(const MessageProcessingInfo &info, Header &header);
smoritaemb 0:580aba13d1a1 345
smoritaemb 0:580aba13d1a1 346 bool deserializeMessage(const MessageProcessingInfo &info,
smoritaemb 0:580aba13d1a1 347 SubmessageHeader &header);
smoritaemb 0:580aba13d1a1 348
smoritaemb 0:580aba13d1a1 349 bool deserializeMessage(const MessageProcessingInfo &info, SubmessageData &msg);
smoritaemb 0:580aba13d1a1 350
smoritaemb 0:580aba13d1a1 351 bool deserializeMessage(const MessageProcessingInfo &info,
smoritaemb 0:580aba13d1a1 352 SubmessageHeartbeat &msg);
smoritaemb 0:580aba13d1a1 353
smoritaemb 0:580aba13d1a1 354 bool deserializeMessage(const MessageProcessingInfo &info,
smoritaemb 0:580aba13d1a1 355 SubmessageAckNack &msg);
smoritaemb 0:580aba13d1a1 356
smoritaemb 0:580aba13d1a1 357 } // namespace rtps
smoritaemb 0:580aba13d1a1 358
smoritaemb 0:580aba13d1a1 359 #endif // RTPS_MESSAGES_H