YARP
Yet Another Robot Platform
PointCloud.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/PointCloud" msg definition:
9 // # This message holds a collection of 3d points, plus optional additional
10 // # information about each point.
11 //
12 // # Time of sensor data acquisition, coordinate frame ID.
13 // Header header
14 //
15 // # Array of 3d points. Each Point32 should be interpreted as a 3d point
16 // # in the frame given in the header.
17 // geometry_msgs/Point32[] points
18 //
19 // # Each channel should have the same number of elements as points array,
20 // # and the data in each channel should correspond 1:1 with each point.
21 // # Channel names in common practice are listed in ChannelFloat32.msg.
22 // ChannelFloat32[] channels
23 // Instances of this class can be read and written with YARP ports,
24 // using a ROS-compatible format.
25 
26 #ifndef YARP_ROSMSG_sensor_msgs_PointCloud_h
27 #define YARP_ROSMSG_sensor_msgs_PointCloud_h
28 
29 #include <yarp/os/Wire.h>
30 #include <yarp/os/Type.h>
31 #include <yarp/os/idl/WireTypes.h>
32 #include <string>
33 #include <vector>
37 
38 namespace yarp {
39 namespace rosmsg {
40 namespace sensor_msgs {
41 
43 {
44 public:
46  std::vector<yarp::rosmsg::geometry_msgs::Point32> points;
47  std::vector<yarp::rosmsg::sensor_msgs::ChannelFloat32> channels;
48 
50  header(),
51  points(),
52  channels()
53  {
54  }
55 
56  void clear()
57  {
58  // *** header ***
59  header.clear();
60 
61  // *** points ***
62  points.clear();
63 
64  // *** channels ***
65  channels.clear();
66  }
67 
68  bool readBare(yarp::os::ConnectionReader& connection) override
69  {
70  // *** header ***
71  if (!header.read(connection)) {
72  return false;
73  }
74 
75  // *** points ***
76  int len = connection.expectInt32();
77  points.resize(len);
78  for (int i=0; i<len; i++) {
79  if (!points[i].read(connection)) {
80  return false;
81  }
82  }
83 
84  // *** channels ***
85  len = connection.expectInt32();
86  channels.resize(len);
87  for (int i=0; i<len; i++) {
88  if (!channels[i].read(connection)) {
89  return false;
90  }
91  }
92 
93  return !connection.isError();
94  }
95 
96  bool readBottle(yarp::os::ConnectionReader& connection) override
97  {
98  connection.convertTextMode();
99  yarp::os::idl::WireReader reader(connection);
100  if (!reader.readListHeader(3)) {
101  return false;
102  }
103 
104  // *** header ***
105  if (!header.read(connection)) {
106  return false;
107  }
108 
109  // *** points ***
110  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
111  return false;
112  }
113  int len = connection.expectInt32();
114  points.resize(len);
115  for (int i=0; i<len; i++) {
116  if (!points[i].read(connection)) {
117  return false;
118  }
119  }
120 
121  // *** channels ***
122  if (connection.expectInt32() != BOTTLE_TAG_LIST) {
123  return false;
124  }
125  len = connection.expectInt32();
126  channels.resize(len);
127  for (int i=0; i<len; i++) {
128  if (!channels[i].read(connection)) {
129  return false;
130  }
131  }
132 
133  return !connection.isError();
134  }
135 
137  bool read(yarp::os::ConnectionReader& connection) override
138  {
139  return (connection.isBareMode() ? readBare(connection)
140  : readBottle(connection));
141  }
142 
143  bool writeBare(yarp::os::ConnectionWriter& connection) const override
144  {
145  // *** header ***
146  if (!header.write(connection)) {
147  return false;
148  }
149 
150  // *** points ***
151  connection.appendInt32(points.size());
152  for (size_t i=0; i<points.size(); i++) {
153  if (!points[i].write(connection)) {
154  return false;
155  }
156  }
157 
158  // *** channels ***
159  connection.appendInt32(channels.size());
160  for (size_t i=0; i<channels.size(); i++) {
161  if (!channels[i].write(connection)) {
162  return false;
163  }
164  }
165 
166  return !connection.isError();
167  }
168 
169  bool writeBottle(yarp::os::ConnectionWriter& connection) const override
170  {
171  connection.appendInt32(BOTTLE_TAG_LIST);
172  connection.appendInt32(3);
173 
174  // *** header ***
175  if (!header.write(connection)) {
176  return false;
177  }
178 
179  // *** points ***
180  connection.appendInt32(BOTTLE_TAG_LIST);
181  connection.appendInt32(points.size());
182  for (size_t i=0; i<points.size(); i++) {
183  if (!points[i].write(connection)) {
184  return false;
185  }
186  }
187 
188  // *** channels ***
189  connection.appendInt32(BOTTLE_TAG_LIST);
190  connection.appendInt32(channels.size());
191  for (size_t i=0; i<channels.size(); i++) {
192  if (!channels[i].write(connection)) {
193  return false;
194  }
195  }
196 
197  connection.convertTextMode();
198  return !connection.isError();
199  }
200 
202  bool write(yarp::os::ConnectionWriter& connection) const override
203  {
204  return (connection.isBareMode() ? writeBare(connection)
205  : writeBottle(connection));
206  }
207 
208  // This class will serialize ROS style or YARP style depending on protocol.
209  // If you need to force a serialization style, use one of these classes:
212 
213  // The name for this message, ROS will need this
214  static constexpr const char* typeName = "sensor_msgs/PointCloud";
215 
216  // The checksum for this message, ROS will need this
217  static constexpr const char* typeChecksum = "d8e9c3f5afbdd8a130fd1d2763945fca";
218 
219  // The source text for this message, ROS will need this
220  static constexpr const char* typeText = "\
221 # This message holds a collection of 3d points, plus optional additional\n\
222 # information about each point.\n\
223 \n\
224 # Time of sensor data acquisition, coordinate frame ID.\n\
225 Header header\n\
226 \n\
227 # Array of 3d points. Each Point32 should be interpreted as a 3d point\n\
228 # in the frame given in the header.\n\
229 geometry_msgs/Point32[] points\n\
230 \n\
231 # Each channel should have the same number of elements as points array,\n\
232 # and the data in each channel should correspond 1:1 with each point.\n\
233 # Channel names in common practice are listed in ChannelFloat32.msg.\n\
234 ChannelFloat32[] channels\n\
235 \n\
236 ================================================================================\n\
237 MSG: std_msgs/Header\n\
238 # Standard metadata for higher-level stamped data types.\n\
239 # This is generally used to communicate timestamped data \n\
240 # in a particular coordinate frame.\n\
241 # \n\
242 # sequence ID: consecutively increasing ID \n\
243 uint32 seq\n\
244 #Two-integer timestamp that is expressed as:\n\
245 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
246 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
247 # time-handling sugar is provided by the client library\n\
248 time stamp\n\
249 #Frame this data is associated with\n\
250 # 0: no frame\n\
251 # 1: global frame\n\
252 string frame_id\n\
253 \n\
254 ================================================================================\n\
255 MSG: geometry_msgs/Point32\n\
256 # This contains the position of a point in free space(with 32 bits of precision).\n\
257 # It is recommeded to use Point wherever possible instead of Point32. \n\
258 # \n\
259 # This recommendation is to promote interoperability. \n\
260 #\n\
261 # This message is designed to take up less space when sending\n\
262 # lots of points at once, as in the case of a PointCloud. \n\
263 \n\
264 float32 x\n\
265 float32 y\n\
266 float32 z\n\
267 ================================================================================\n\
268 MSG: sensor_msgs/ChannelFloat32\n\
269 # This message is used by the PointCloud message to hold optional data\n\
270 # associated with each point in the cloud. The length of the values\n\
271 # array should be the same as the length of the points array in the\n\
272 # PointCloud, and each value should be associated with the corresponding\n\
273 # point.\n\
274 \n\
275 # Channel names in existing practice include:\n\
276 # \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\
277 # This is opposite to usual conventions but remains for\n\
278 # historical reasons. The newer PointCloud2 message has no\n\
279 # such problem.\n\
280 # \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\
281 # (R,G,B) values packed into the least significant 24 bits,\n\
282 # in order.\n\
283 # \"intensity\" - laser or pixel intensity.\n\
284 # \"distance\"\n\
285 \n\
286 # The channel name should give semantics of the channel (e.g.\n\
287 # \"intensity\" instead of \"value\").\n\
288 string name\n\
289 \n\
290 # The values array should be 1-1 with the elements of the associated\n\
291 # PointCloud.\n\
292 float32[] values\n\
293 ";
294 
295  yarp::os::Type getType() const override
296  {
298  typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
299  typ.addProperty("message_definition", yarp::os::Value(typeText));
300  return typ;
301  }
302 };
303 
304 } // namespace sensor_msgs
305 } // namespace rosmsg
306 } // namespace yarp
307 
308 #endif // YARP_ROSMSG_sensor_msgs_PointCloud_h
#define BOTTLE_TAG_LIST
Definition: Bottle.h:28
An interface for reading from a 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
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 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.
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
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
Definition: PointCloud.h:137
yarp::rosmsg::std_msgs::Header header
Definition: PointCloud.h:45
bool readBare(yarp::os::ConnectionReader &connection) override
Definition: PointCloud.h:68
std::vector< yarp::rosmsg::sensor_msgs::ChannelFloat32 > channels
Definition: PointCloud.h:47
yarp::os::Type getType() const override
Definition: PointCloud.h:295
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::PointCloud > rosStyle
Definition: PointCloud.h:210
bool readBottle(yarp::os::ConnectionReader &connection) override
Definition: PointCloud.h:96
static constexpr const char * typeChecksum
Definition: PointCloud.h:217
static constexpr const char * typeName
Definition: PointCloud.h:214
bool writeBare(yarp::os::ConnectionWriter &connection) const override
Definition: PointCloud.h:143
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::PointCloud > bottleStyle
Definition: PointCloud.h:211
static constexpr const char * typeText
Definition: PointCloud.h:220
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Definition: PointCloud.h:169
std::vector< yarp::rosmsg::geometry_msgs::Point32 > points
Definition: PointCloud.h:46
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
Definition: PointCloud.h:202
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