YARP
Yet Another Robot Platform
PointCloud2.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  * All rights reserved.
4  *
5  * This software may be modified and distributed under the terms of the
6  * BSD-3-Clause license. See the accompanying LICENSE file for details.
7  */
8 
9 // This is an automatically generated file.
10 
11 // Generated from the following "sensor_msgs/PointCloud2" msg definition:
12 // # This message holds a collection of N-dimensional points, which may
13 // # contain additional information such as normals, intensity, etc. The
14 // # point data is stored as a binary blob, its layout described by the
15 // # contents of the "fields" array.
16 //
17 // # The point cloud data may be organized 2d (image-like) or 1d
18 // # (unordered). Point clouds organized as 2d images may be produced by
19 // # camera depth sensors such as stereo or time-of-flight.
20 //
21 // # Time of sensor data acquisition, and the coordinate frame ID (for 3d
22 // # points).
23 // Header header
24 //
25 // # 2D structure of the point cloud. If the cloud is unordered, height is
26 // # 1 and width is the length of the point cloud.
27 // uint32 height
28 // uint32 width
29 //
30 // # Describes the channels and their layout in the binary data blob.
31 // PointField[] fields
32 //
33 // bool is_bigendian # Is this data bigendian?
34 // uint32 point_step # Length of a point in bytes
35 // uint32 row_step # Length of a row in bytes
36 // uint8[] data # Actual point data, size is (row_step*height)
37 //
38 // bool is_dense # True if there are no invalid points
39 // Instances of this class can be read and written with YARP ports,
40 // using a ROS-compatible format.
41 
42 #ifndef YARP_ROSMSG_sensor_msgs_PointCloud2_h
43 #define YARP_ROSMSG_sensor_msgs_PointCloud2_h
44 
45 #include <yarp/os/Wire.h>
46 #include <yarp/os/Type.h>
47 #include <yarp/os/idl/WireTypes.h>
48 #include <string>
49 #include <vector>
52 
53 namespace yarp {
54 namespace rosmsg {
55 namespace sensor_msgs {
56 
58 {
59 public:
61  std::uint32_t height;
62  std::uint32_t width;
63  std::vector<yarp::rosmsg::sensor_msgs::PointField> fields;
65  std::uint32_t point_step;
66  std::uint32_t row_step;
67  std::vector<std::uint8_t> data;
68  bool is_dense;
69 
71  header(),
72  height(0),
73  width(0),
74  fields(),
75  is_bigendian(false),
76  point_step(0),
77  row_step(0),
78  data(),
79  is_dense(false)
80  {
81  }
82 
83  void clear()
84  {
85  // *** header ***
86  header.clear();
87 
88  // *** height ***
89  height = 0;
90 
91  // *** width ***
92  width = 0;
93 
94  // *** fields ***
95  fields.clear();
96 
97  // *** is_bigendian ***
98  is_bigendian = false;
99 
100  // *** point_step ***
101  point_step = 0;
102 
103  // *** row_step ***
104  row_step = 0;
105 
106  // *** data ***
107  data.clear();
108 
109  // *** is_dense ***
110  is_dense = false;
111  }
112 
113  bool readBare(yarp::os::ConnectionReader& connection) override
114  {
115  // *** header ***
116  if (!header.read(connection)) {
117  return false;
118  }
119 
120  // *** height ***
121  height = connection.expectInt32();
122 
123  // *** width ***
124  width = connection.expectInt32();
125 
126  // *** fields ***
127  int len = connection.expectInt32();
128  fields.resize(len);
129  for (int i=0; i<len; i++) {
130  if (!fields[i].read(connection)) {
131  return false;
132  }
133  }
134 
135  // *** is_bigendian ***
136  if (!connection.expectBlock((char*)&is_bigendian, 1)) {
137  return false;
138  }
139 
140  // *** point_step ***
141  point_step = connection.expectInt32();
142 
143  // *** row_step ***
144  row_step = connection.expectInt32();
145 
146  // *** data ***
147  len = connection.expectInt32();
148  data.resize(len);
149  if (len > 0 && !connection.expectBlock((char*)&data[0], sizeof(std::uint8_t)*len)) {
150  return false;
151  }
152 
153  // *** is_dense ***
154  if (!connection.expectBlock((char*)&is_dense, 1)) {
155  return false;
156  }
157 
158  return !connection.isError();
159  }
160 
161  bool readBottle(yarp::os::ConnectionReader& connection) override
162  {
163  connection.convertTextMode();
164  yarp::os::idl::WireReader reader(connection);
165  if (!reader.readListHeader(9)) {
166  return false;
167  }
168 
169  // *** header ***
170  if (!header.read(connection)) {
171  return false;
172  }
173 
174  // *** height ***
175  height = reader.expectInt32();
176 
177  // *** width ***
178  width = reader.expectInt32();
179 
180  // *** fields ***
181  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
182  return false;
183  }
184  int len = connection.expectInt32();
185  fields.resize(len);
186  for (int i=0; i<len; i++) {
187  if (!fields[i].read(connection)) {
188  return false;
189  }
190  }
191 
192  // *** is_bigendian ***
193  is_bigendian = reader.expectInt8();
194 
195  // *** point_step ***
196  point_step = reader.expectInt32();
197 
198  // *** row_step ***
199  row_step = reader.expectInt32();
200 
201  // *** data ***
202  if (connection.expectInt32() != (BOTTLE_TAG_LIST|BOTTLE_TAG_INT8)) {
203  return false;
204  }
205  len = connection.expectInt32();
206  data.resize(len);
207  for (int i=0; i<len; i++) {
208  data[i] = (std::uint8_t)connection.expectInt8();
209  }
210 
211  // *** is_dense ***
212  is_dense = reader.expectInt8();
213 
214  return !connection.isError();
215  }
216 
218  bool read(yarp::os::ConnectionReader& connection) override
219  {
220  return (connection.isBareMode() ? readBare(connection)
221  : readBottle(connection));
222  }
223 
224  bool writeBare(yarp::os::ConnectionWriter& connection) const override
225  {
226  // *** header ***
227  if (!header.write(connection)) {
228  return false;
229  }
230 
231  // *** height ***
232  connection.appendInt32(height);
233 
234  // *** width ***
235  connection.appendInt32(width);
236 
237  // *** fields ***
238  connection.appendInt32(fields.size());
239  for (size_t i=0; i<fields.size(); i++) {
240  if (!fields[i].write(connection)) {
241  return false;
242  }
243  }
244 
245  // *** is_bigendian ***
246  connection.appendBlock((char*)&is_bigendian, 1);
247 
248  // *** point_step ***
249  connection.appendInt32(point_step);
250 
251  // *** row_step ***
252  connection.appendInt32(row_step);
253 
254  // *** data ***
255  connection.appendInt32(data.size());
256  if (data.size()>0) {
257  connection.appendExternalBlock((char*)&data[0], sizeof(std::uint8_t)*data.size());
258  }
259 
260  // *** is_dense ***
261  connection.appendBlock((char*)&is_dense, 1);
262 
263  return !connection.isError();
264  }
265 
266  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
267  {
268  connection.appendInt32(BOTTLE_TAG_LIST);
269  connection.appendInt32(9);
270 
271  // *** header ***
272  if (!header.write(connection)) {
273  return false;
274  }
275 
276  // *** height ***
277  connection.appendInt32(BOTTLE_TAG_INT32);
278  connection.appendInt32(height);
279 
280  // *** width ***
281  connection.appendInt32(BOTTLE_TAG_INT32);
282  connection.appendInt32(width);
283 
284  // *** fields ***
285  connection.appendInt32(BOTTLE_TAG_LIST);
286  connection.appendInt32(fields.size());
287  for (size_t i=0; i<fields.size(); i++) {
288  if (!fields[i].write(connection)) {
289  return false;
290  }
291  }
292 
293  // *** is_bigendian ***
294  connection.appendInt32(BOTTLE_TAG_INT8);
295  connection.appendInt8(is_bigendian);
296 
297  // *** point_step ***
298  connection.appendInt32(BOTTLE_TAG_INT32);
299  connection.appendInt32(point_step);
300 
301  // *** row_step ***
302  connection.appendInt32(BOTTLE_TAG_INT32);
303  connection.appendInt32(row_step);
304 
305  // *** data ***
307  connection.appendInt32(data.size());
308  for (size_t i=0; i<data.size(); i++) {
309  connection.appendInt8(data[i]);
310  }
311 
312  // *** is_dense ***
313  connection.appendInt32(BOTTLE_TAG_INT8);
314  connection.appendInt8(is_dense);
315 
316  connection.convertTextMode();
317  return !connection.isError();
318  }
319 
321  bool write(yarp::os::ConnectionWriter& connection) const override
322  {
323  return (connection.isBareMode() ? writeBare(connection)
324  : writeBottle(connection));
325  }
326 
327  // This class will serialize ROS style or YARP style depending on protocol.
328  // If you need to force a serialization style, use one of these classes:
331 
332  // The name for this message, ROS will need this
333  static constexpr const char* typeName = "sensor_msgs/PointCloud2";
334 
335  // The checksum for this message, ROS will need this
336  static constexpr const char* typeChecksum = "1158d486dd51d683ce2f1be655c3c181";
337 
338  // The source text for this message, ROS will need this
339  static constexpr const char* typeText = "\
340 # This message holds a collection of N-dimensional points, which may\n\
341 # contain additional information such as normals, intensity, etc. The\n\
342 # point data is stored as a binary blob, its layout described by the\n\
343 # contents of the \"fields\" array.\n\
344 \n\
345 # The point cloud data may be organized 2d (image-like) or 1d\n\
346 # (unordered). Point clouds organized as 2d images may be produced by\n\
347 # camera depth sensors such as stereo or time-of-flight.\n\
348 \n\
349 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\
350 # points).\n\
351 Header header\n\
352 \n\
353 # 2D structure of the point cloud. If the cloud is unordered, height is\n\
354 # 1 and width is the length of the point cloud.\n\
355 uint32 height\n\
356 uint32 width\n\
357 \n\
358 # Describes the channels and their layout in the binary data blob.\n\
359 PointField[] fields\n\
360 \n\
361 bool is_bigendian # Is this data bigendian?\n\
362 uint32 point_step # Length of a point in bytes\n\
363 uint32 row_step # Length of a row in bytes\n\
364 uint8[] data # Actual point data, size is (row_step*height)\n\
365 \n\
366 bool is_dense # True if there are no invalid points\n\
367 \n\
368 ================================================================================\n\
369 MSG: std_msgs/Header\n\
370 # Standard metadata for higher-level stamped data types.\n\
371 # This is generally used to communicate timestamped data \n\
372 # in a particular coordinate frame.\n\
373 # \n\
374 # sequence ID: consecutively increasing ID \n\
375 uint32 seq\n\
376 #Two-integer timestamp that is expressed as:\n\
377 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
378 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
379 # time-handling sugar is provided by the client library\n\
380 time stamp\n\
381 #Frame this data is associated with\n\
382 # 0: no frame\n\
383 # 1: global frame\n\
384 string frame_id\n\
385 \n\
386 ================================================================================\n\
387 MSG: sensor_msgs/PointField\n\
388 # This message holds the description of one point entry in the\n\
389 # PointCloud2 message format.\n\
390 uint8 INT8 = 1\n\
391 uint8 UINT8 = 2\n\
392 uint8 INT16 = 3\n\
393 uint8 UINT16 = 4\n\
394 uint8 INT32 = 5\n\
395 uint8 UINT32 = 6\n\
396 uint8 FLOAT32 = 7\n\
397 uint8 FLOAT64 = 8\n\
398 \n\
399 string name # Name of field\n\
400 uint32 offset # Offset from start of point struct\n\
401 uint8 datatype # Datatype enumeration, see above\n\
402 uint32 count # How many elements in the field\n\
403 ";
404 
405  yarp::os::Type getType() const override
406  {
408  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
409  typ.addProperty("message_definition", yarp::os::Value(typeText));
410  return typ;
411  }
412 };
413 
414 } // namespace sensor_msgs
415 } // namespace rosmsg
416 } // namespace yarp
417 
418 #endif // YARP_ROSMSG_sensor_msgs_PointCloud2_h
yarp::rosmsg::sensor_msgs::PointCloud2::row_step
std::uint32_t row_step
Definition: PointCloud2.h:66
yarp::rosmsg::sensor_msgs::PointCloud2::writeBare
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: PointCloud2.h:224
yarp::rosmsg::sensor_msgs::PointCloud2::is_bigendian
bool is_bigendian
Definition: PointCloud2.h:64
yarp::rosmsg::std_msgs::Header::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: Header.h:115
yarp::rosmsg::sensor_msgs::PointCloud2::getType
yarp::os::Type getType() const override
Definition: PointCloud2.h:405
yarp::os::ConnectionWriter::appendBlock
virtual void appendBlock(const char *data, size_t len)=0
Send a block of data to the network connection.
yarp::rosmsg::sensor_msgs::PointCloud2::typeName
static constexpr const char * typeName
Definition: PointCloud2.h:333
yarp::rosmsg::sensor_msgs::PointCloud2
Definition: PointCloud2.h:58
yarp::rosmsg::sensor_msgs::PointCloud2::typeText
static constexpr const char * typeText
Definition: PointCloud2.h:339
WireTypes.h
BOTTLE_TAG_LIST
#define BOTTLE_TAG_LIST
Definition: Bottle.h:30
yarp::rosmsg::sensor_msgs::PointCloud2::writeBottle
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: PointCloud2.h:266
yarp::os::idl::BottleStyle
Definition: BottleStyle.h:22
PointField.h
yarp::os::Type
Definition: Type.h:24
yarp::rosmsg::sensor_msgs::PointCloud2::point_step
std::uint32_t point_step
Definition: PointCloud2.h:65
yarp::rosmsg::sensor_msgs::PointCloud2::typeChecksum
static constexpr const char * typeChecksum
Definition: PointCloud2.h:336
yarp::rosmsg::sensor_msgs::PointCloud2::clear
void clear()
Definition: PointCloud2.h:83
yarp::os::idl::WirePortable::read
virtual bool read(yarp::os::idl::WireReader &reader)
Definition: WirePortable.cpp:14
Header.h
yarp::os::ConnectionWriter::appendInt8
virtual void appendInt8(std::int8_t data)=0
Send a representation of a 8-bit integer to the network connection.
yarp::os::ConnectionReader::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::std_msgs::Header::clear
void clear()
Definition: Header.h:58
Wire.h
yarp::rosmsg::sensor_msgs::PointCloud2::PointCloud2
PointCloud2()
Definition: PointCloud2.h:70
BOTTLE_TAG_INT8
#define BOTTLE_TAG_INT8
Definition: Bottle.h:21
yarp::rosmsg::sensor_msgs::PointCloud2::fields
std::vector< yarp::rosmsg::sensor_msgs::PointField > fields
Definition: PointCloud2.h:63
yarp::rosmsg::sensor_msgs::PointCloud2::readBare
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: PointCloud2.h:113
yarp::os::ConnectionReader::expectInt8
virtual std::int8_t expectInt8()=0
Read a 8-bit integer from the network connection.
BOTTLE_TAG_INT32
#define BOTTLE_TAG_INT32
Definition: Bottle.h:23
yarp::os::ConnectionWriter::isError
virtual bool isError() const =0
yarp::os::Type::byName
static Type byName(const char *name)
Definition: Type.cpp:174
yarp::os::ConnectionReader::expectInt32
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
yarp::rosmsg::sensor_msgs::PointCloud2::readBottle
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: PointCloud2.h:161
yarp::os::Type::addProperty
Type & addProperty(const char *key, const Value &val)
Definition: Type.cpp:137
Type.h
yarp::os::ConnectionWriter
An interface for writing to a network connection.
Definition: ConnectionWriter.h:40
yarp::os::ConnectionReader::isError
virtual bool isError() const =0
yarp::rosmsg::sensor_msgs::PointCloud2::height
std::uint32_t height
Definition: PointCloud2.h:61
yarp::os::ConnectionReader::convertTextMode
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
yarp::rosmsg::sensor_msgs::PointCloud2::header
yarp::rosmsg::std_msgs::Header header
Definition: PointCloud2.h:60
yarp::os::idl::WirePortable
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:26
yarp::os::ConnectionWriter::isBareMode
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::rosmsg::std_msgs::Header::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: Header.h:162
yarp::os::ConnectionWriter::convertTextMode
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
yarp::rosmsg::sensor_msgs::PointCloud2::write
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: PointCloud2.h:321
yarp::os::ConnectionWriter::appendInt32
virtual void appendInt32(std::int32_t data)=0
Send a representation of a 32-bit integer to the network connection.
yarp::os::idl::WireReader
IDL-friendly connection reader.
Definition: WireReader.h:33
yarp::os::ConnectionReader
An interface for reading from a network connection.
Definition: ConnectionReader.h:40
yarp::os::idl::BareStyle
Definition: BareStyle.h:22
yarp::rosmsg::sensor_msgs::PointCloud2::width
std::uint32_t width
Definition: PointCloud2.h:62
yarp::os::idl::WireReader::expectInt32
std::int32_t expectInt32()
Definition: WireReader.h:99
yarp::rosmsg::sensor_msgs::PointCloud2::bottleStyle
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::PointCloud2 > bottleStyle
Definition: PointCloud2.h:330
yarp
The main, catch-all namespace for YARP.
Definition: environment.h:18
yarp::os::idl::WireReader::expectInt8
std::int8_t expectInt8()
Definition: WireReader.h:87
yarp::os::ConnectionWriter::appendExternalBlock
virtual void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
yarp::os::ConnectionReader::expectBlock
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
yarp::os::Value
A single value (typically within a Bottle).
Definition: Value.h:47
sensor_msgs
Definition: BatteryState.h:22
yarp::rosmsg::std_msgs::Header
Definition: Header.h:45
yarp::rosmsg::sensor_msgs::PointCloud2::data
std::vector< std::uint8_t > data
Definition: PointCloud2.h:67
yarp::rosmsg::sensor_msgs::PointCloud2::rosStyle
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::PointCloud2 > rosStyle
Definition: PointCloud2.h:329
yarp::rosmsg::sensor_msgs::PointCloud2::is_dense
bool is_dense
Definition: PointCloud2.h:68
yarp::rosmsg::sensor_msgs::PointCloud2::read
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: PointCloud2.h:218
yarp::os::idl::WireReader::readListHeader
bool readListHeader()
Definition: WireReader.cpp:470
yarp::os::idl::WirePortable::write
virtual bool write(const yarp::os::idl::WireWriter &writer) const
Definition: WirePortable.cpp:20