shape_shifter.cpp
Go to the documentation of this file.
1 // SPDX-License-Identifier: BSD-3-Clause
2 // SPDX-FileCopyrightText: Czech Technical University in Prague
3 
10 // HACK begin we need to access many private fields of topic_tools::ShapeShifter
11 #include <sstream>
12 #define private public
13 #include <topic_tools/shape_shifter.h>
14 #undef private
15 // HACK end
16 
17 
18 #include <algorithm>
19 #include <utility>
20 
21 #include <boost/shared_ptr.hpp>
22 
23 #include <ros/common.h>
24 #include <ros/serialization.h>
25 #include <std_msgs/Header.h>
26 
29 
31 
32 namespace cras
33 {
34 
35 #if ROS_VERSION_MINIMUM(1, 15, 0)
36 
38 {
39  return msg.msgBuf.data();
40 }
41 
42 const uint8_t* getBuffer(const topic_tools::ShapeShifter& msg)
43 {
44  return msg.msgBuf.data();
45 }
46 
47 void resizeBuffer(topic_tools::ShapeShifter& msg, size_t newLength)
48 {
49  if (newLength == msg.size())
50  return;
51  // resize() makes sure that if the buffer was reallocated, the start of the old buffer will get copied to the new one
52  msg.msgBuf.resize(newLength);
53 }
54 
56 {
57  out = in;
58 }
59 
60 #else
61 
63 {
64  return msg.msgBuf;
65 }
66 
67 const uint8_t* getBuffer(const topic_tools::ShapeShifter& msg)
68 {
69  return msg.msgBuf;
70 }
71 
72 void resizeBuffer(topic_tools::ShapeShifter& msg, size_t newLength)
73 {
74  if (newLength == msg.size())
75  return;
76  if (newLength < msg.size())
77  {
78  msg.msgBufUsed = newLength;
79  }
80  else
81  {
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;
87  // Not exactly needed, but to keep compatibility with the Noetic version
88  std::memcpy(msg.msgBuf, oldBuf, oldLength);
89  delete[] oldBuf;
90  }
91 }
92 
94 {
95  out = in;
96  out.msgBuf = new uint8_t[in.msgBufUsed];
97  out.msgBufAlloc = in.msgBufUsed;
98  std::memcpy(out.msgBuf, in.msgBuf, in.msgBufUsed);
99 }
100 
101 #endif
102 
104 {
105  return msg.size();
106 }
107 
109 {
110  const auto lines = cras::split(msg.getMessageDefinition(), "\n");
111  for (const auto& line : lines)
112  {
113  const auto strippedLine = cras::stripLeading(line);
114  if (strippedLine.empty() || strippedLine[0] == '#' || /* constants */ cras::contains(strippedLine, '='))
115  continue;
116  // Header has to be the first non-comment line, so as soon as we find one, we return
117  return cras::startsWith(strippedLine, "Header header");
118  }
119  return false;
120 }
121 
122 cras::optional<std_msgs::Header> getHeader(const topic_tools::ShapeShifter& msg)
123 {
124  try
125  {
126  auto p = boost::make_shared<std_msgs::Header>();
127 
130 
131  return *p;
132  }
133  catch (...)
134  {
135  return cras::nullopt;
136  }
137 }
138 
139 bool setHeader(topic_tools::ShapeShifter& msg, std_msgs::Header& header)
140 {
141  const auto oldHeader = cras::getHeader(msg);
142  if (!oldHeader.has_value())
143  return false;
144 
145  const auto oldHeaderLength = ros::serialization::serializationLength(oldHeader.value());
146  const auto newHeaderLength = ros::serialization::serializationLength(header);
147  const auto oldLength = msg.size();
148  const auto newLength = oldLength + newHeaderLength - oldHeaderLength;
149 
150  if (oldHeaderLength == newHeaderLength)
151  {
152  // New message is same length as the old one - we just overwrite the header
153  try
154  {
157  return true;
158  }
159  catch (...)
160  {
161  return false;
162  }
163  }
164  else if (newHeaderLength < oldHeaderLength)
165  {
166  // New message is shorter - we just move the data part to the left
167  cras::resizeBuffer(msg, newLength); // The buffer remains the same.
168  auto buffer = cras::getBuffer(msg);
169  try
170  {
171  ros::serialization::OStream ostream(buffer, newLength);
173  std::memmove(buffer + newHeaderLength, buffer + oldHeaderLength, oldLength - oldHeaderLength);
174  return true;
175  }
176  catch (...)
177  {
178  return false;
179  }
180  }
181  else
182  {
183  // New message is longer - we need to reallocate the buffer, move its data to the right and then write new header
184  cras::resizeBuffer(msg, newLength); // buffer contents are copied to the reallocated one
185  auto buffer = cras::getBuffer(msg);
186  std::memmove(buffer + newHeaderLength, buffer + oldHeaderLength, oldLength - oldHeaderLength);
187  try
188  {
189  ros::serialization::OStream ostream(buffer, newLength);
191  return true;
192  }
193  catch (...)
194  {
195  return false;
196  }
197  }
198 }
199 
200 #if ROS_VERSION_MINIMUM(1, 15, 0)
201 #else
202 
203 ShapeShifter::ShapeShifter() = default;
204 ShapeShifter::~ShapeShifter() = default;
205 
207  ShapeShifter(reinterpret_cast<const ShapeShifter&>(other))
208 {
209 }
210 
211 ShapeShifter::ShapeShifter(topic_tools::ShapeShifter && other) noexcept :
212  ShapeShifter(reinterpret_cast<ShapeShifter &&>(other))
213 {
214 }
215 
216 ShapeShifter& ShapeShifter::operator=(const topic_tools::ShapeShifter& other)
217 {
218  return operator=(reinterpret_cast<const ShapeShifter&>(other));
219 }
220 
221 ShapeShifter& ShapeShifter::operator=(topic_tools::ShapeShifter && other) noexcept
222 {
223  return operator=(reinterpret_cast<ShapeShifter &&>(other));
224 }
225 
226 ShapeShifter::ShapeShifter(const ShapeShifter& other)
227 {
228  this->md5 = other.md5;
229  this->datatype = other.datatype;
230  this->msg_def = other.msg_def;
231  this->latching = other.latching;
232  this->typed = other.typed;
233  this->msgBufUsed = this->msgBufAlloc = other.msgBufUsed;
234  if (other.msgBuf != nullptr && other.msgBufUsed > 0)
235  {
236  this->msgBuf = new uint8_t[other.msgBufUsed];
237  memcpy(this->msgBuf, other.msgBuf, other.msgBufUsed);
238  }
239 }
240 
241 ShapeShifter::ShapeShifter(ShapeShifter && other) noexcept
242 {
243  this->md5 = other.md5;
244  this->datatype = other.datatype;
245  this->msg_def = other.msg_def;
246  this->latching = other.latching;
247  this->typed = other.typed;
248  this->msgBufUsed = this->msgBufAlloc = other.msgBufUsed;
249  if (other.msgBuf != nullptr && other.msgBufUsed > 0)
250  {
251  this->msgBuf = std::exchange(other.msgBuf, nullptr);
252  other.msgBufAlloc = 0;
253  other.msgBufUsed = 0;
254  }
255 }
256 
257 ShapeShifter& ShapeShifter::operator=(const ShapeShifter& other)
258 {
259  if (this == &other)
260  return *this;
261 
262  this->md5 = other.md5;
263  this->datatype = other.datatype;
264  this->msg_def = other.msg_def;
265  this->latching = other.latching;
266  this->typed = other.typed;
267  this->msgBufUsed = other.msgBufUsed;
268  if (other.msgBuf != nullptr && other.msgBufUsed > 0)
269  {
270  if (this->msgBufAlloc < other.msgBufUsed)
271  {
272  delete[] this->msgBuf;
273  this->msgBuf = new uint8_t[other.msgBufUsed];
274  this->msgBufAlloc = other.msgBufUsed;
275  }
276  memcpy(this->msgBuf, other.msgBuf, other.msgBufUsed);
277  }
278  else if (this->msgBuf != nullptr)
279  {
280  delete[] this->msgBuf;
281  this->msgBuf = nullptr;
282  this->msgBufAlloc = 0;
283  }
284  return *this;
285 }
286 
287 ShapeShifter& ShapeShifter::operator=(ShapeShifter && other) noexcept
288 {
289  if (this == &other)
290  return *this;
291 
292  this->md5 = other.md5;
293  this->datatype = other.datatype;
294  this->msg_def = other.msg_def;
295  this->latching = other.latching;
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);
300  return *this;
301 }
302 
303 #endif
304 
305 }
optional.hpp
ros::serialization::OStream
cras::contains
bool contains(const ::std::string &str, char c)
msg
msg
ros::serialization::deserialize
void deserialize(Stream &stream, boost::array< T, N > &t)
cras
cras::hasHeader
bool hasHeader(const ::topic_tools::ShapeShifter &msg)
Tell whether the given message has header field.
topic_tools::ShapeShifter::md5
std::string md5
shape_shifter.h
Tools for more convenient working with ShapeShifter objects.
topic_tools::ShapeShifter::datatype
std::string datatype
s
XmlRpcServer s
cras::stripLeading
void stripLeading(::std::string &s, const char &c=' ')
ros::serialization::serializationLength
uint32_t serializationLength(const boost::array< T, N > &t)
ros::serialization::IStream
cras::ShapeShifter
ShapeShifter class with fixed behavior on copy/move on Melodic. Use this class everywhere possible to...
Definition: shape_shifter.h:116
topic_tools::ShapeShifter::latching
std::string latching
cras::startsWith
bool startsWith(const ::std::string &str, const ::std::string &prefix)
string_utils.hpp
serialization.h
topic_tools::ShapeShifter::typed
bool typed
cras::getBufferLength
size_t getBufferLength(const ::topic_tools::ShapeShifter &msg)
Get the length of the internal buffer with serialized message data.
cras::split
::std::vector<::std::string > split(const ::std::string &str, const ::std::string &delimiter, int maxSplits=-1)
cras::copyShapeShifter
void copyShapeShifter(const ::topic_tools::ShapeShifter &in, ::topic_tools::ShapeShifter &out)
Copy in ShapeShifter to out.
cras::getBuffer
uint8_t * getBuffer(::topic_tools::ShapeShifter &msg)
Get the internal buffer with serialized message data.
datatype
const char * datatype()
topic_tools::ShapeShifter::msgBuf
std::vector< uint8_t > msgBuf
topic_tools::ShapeShifter
header
const std::string header
cras::ShapeShifter::ShapeShifter
ShapeShifter()
ros::serialization::serialize
void serialize(Stream &stream, const boost::array< T, N > &t)
cras::getHeader
::cras::optional<::std_msgs::Header > getHeader(const ::topic_tools::ShapeShifter &msg)
Get the header field of the given message, if it has any.
topic_tools::ShapeShifter::msg_def
std::string msg_def
cras::resizeBuffer
void resizeBuffer(::topic_tools::ShapeShifter &msg, size_t newLength)
Resize the internal buffer of the message.
cras::ShapeShifter::~ShapeShifter
~ShapeShifter() override
cras::setHeader
bool setHeader(::topic_tools::ShapeShifter &msg, ::std_msgs::Header &header)
Change the header field of the given message, if it has any.


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sat Sep 14 2024 02:49:55