12 #define private public
13 #include <topic_tools/shape_shifter.h>
21 #include <boost/shared_ptr.hpp>
23 #include <ros/common.h>
25 #include <std_msgs/Header.h>
35 #if ROS_VERSION_MINIMUM(1, 15, 0)
39 return msg.msgBuf.data();
44 return msg.msgBuf.data();
49 if (newLength ==
msg.size())
52 msg.msgBuf.resize(newLength);
74 if (newLength ==
msg.size())
76 if (newLength <
msg.size())
78 msg.msgBufUsed = newLength;
82 auto oldBuf =
msg.msgBuf;
83 const auto oldLength =
msg.msgBufUsed;
84 msg.msgBuf =
new uint8_t[newLength];
85 msg.msgBufAlloc = newLength;
86 msg.msgBufUsed = newLength;
88 std::memcpy(
msg.msgBuf, oldBuf, oldLength);
96 out.
msgBuf =
new uint8_t[in.msgBufUsed];
97 out.msgBufAlloc = in.msgBufUsed;
111 for (
const auto& line : lines)
114 if (strippedLine.empty() || strippedLine[0] ==
'#' ||
cras::contains(strippedLine,
'='))
126 auto p = boost::make_shared<std_msgs::Header>();
135 return cras::nullopt;
142 if (!oldHeader.has_value())
147 const auto oldLength =
msg.size();
148 const auto newLength = oldLength + newHeaderLength - oldHeaderLength;
150 if (oldHeaderLength == newHeaderLength)
164 else if (newHeaderLength < oldHeaderLength)
173 std::memmove(buffer + newHeaderLength, buffer + oldHeaderLength, oldLength - oldHeaderLength);
186 std::memmove(buffer + newHeaderLength, buffer + oldHeaderLength, oldLength - oldHeaderLength);
200 #if ROS_VERSION_MINIMUM(1, 15, 0)
207 ShapeShifter(reinterpret_cast<const ShapeShifter&>(other))
212 ShapeShifter(
reinterpret_cast<ShapeShifter &&
>(other))
218 return operator=(
reinterpret_cast<const ShapeShifter&
>(other));
223 return operator=(
reinterpret_cast<ShapeShifter &&
>(other));
228 this->md5 = other.
md5;
232 this->typed = other.
typed;
233 this->msgBufUsed = this->msgBufAlloc = other.msgBufUsed;
234 if (other.
msgBuf !=
nullptr && other.msgBufUsed > 0)
236 this->msgBuf =
new uint8_t[other.msgBufUsed];
237 memcpy(this->msgBuf, other.
msgBuf, other.msgBufUsed);
243 this->md5 = other.
md5;
247 this->typed = other.
typed;
248 this->msgBufUsed = this->msgBufAlloc = other.msgBufUsed;
249 if (other.
msgBuf !=
nullptr && other.msgBufUsed > 0)
251 this->msgBuf = std::exchange(other.
msgBuf,
nullptr);
252 other.msgBufAlloc = 0;
253 other.msgBufUsed = 0;
262 this->md5 = other.
md5;
266 this->typed = other.
typed;
267 this->msgBufUsed = other.msgBufUsed;
268 if (other.
msgBuf !=
nullptr && other.msgBufUsed > 0)
270 if (this->msgBufAlloc < other.msgBufUsed)
272 delete[] this->msgBuf;
273 this->msgBuf =
new uint8_t[other.msgBufUsed];
274 this->msgBufAlloc = other.msgBufUsed;
276 memcpy(this->msgBuf, other.
msgBuf, other.msgBufUsed);
278 else if (this->msgBuf !=
nullptr)
280 delete[] this->msgBuf;
281 this->msgBuf =
nullptr;
282 this->msgBufAlloc = 0;
292 this->md5 = other.
md5;
296 this->typed = other.
typed;
297 std::swap(this->msgBufUsed, other.msgBufUsed);
298 std::swap(this->msgBufAlloc, other.msgBufAlloc);
299 std::swap(this->msgBuf, other.
msgBuf);