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