YARP
Yet Another Robot Platform
MultiEchoLaserScan.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/MultiEchoLaserScan" msg definition:
9// # Single scan from a multi-echo planar laser range-finder
10// #
11// # If you have another ranging device with different behavior (e.g. a sonar
12// # array), please find or create a different message, since applications
13// # will make fairly laser-specific assumptions about this data
14//
15// Header header # timestamp in the header is the acquisition time of
16// # the first ray in the scan.
17// #
18// # in frame frame_id, angles are measured around
19// # the positive Z axis (counterclockwise, if Z is up)
20// # with zero angle being forward along the x axis
21//
22// float32 angle_min # start angle of the scan [rad]
23// float32 angle_max # end angle of the scan [rad]
24// float32 angle_increment # angular distance between measurements [rad]
25//
26// float32 time_increment # time between measurements [seconds] - if your scanner
27// # is moving, this will be used in interpolating position
28// # of 3d points
29// float32 scan_time # time between scans [seconds]
30//
31// float32 range_min # minimum range value [m]
32// float32 range_max # maximum range value [m]
33//
34// LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded)
35// # +Inf measurements are out of range
36// # -Inf measurements are too close to determine exact distance.
37// LaserEcho[] intensities # intensity data [device-specific units]. If your
38// # device does not provide intensities, please leave
39// # the array empty.// 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_MultiEchoLaserScan_h
43#define YARP_ROSMSG_sensor_msgs_MultiEchoLaserScan_h
44
45#include <yarp/os/Wire.h>
46#include <yarp/os/Type.h>
48#include <string>
49#include <vector>
52
53namespace yarp {
54namespace rosmsg {
55namespace sensor_msgs {
56
58{
59public:
61 yarp::conf::float32_t angle_min;
62 yarp::conf::float32_t angle_max;
63 yarp::conf::float32_t angle_increment;
64 yarp::conf::float32_t time_increment;
65 yarp::conf::float32_t scan_time;
66 yarp::conf::float32_t range_min;
67 yarp::conf::float32_t range_max;
68 std::vector<yarp::rosmsg::sensor_msgs::LaserEcho> ranges;
69 std::vector<yarp::rosmsg::sensor_msgs::LaserEcho> intensities;
70
72 header(),
73 angle_min(0.0f),
74 angle_max(0.0f),
75 angle_increment(0.0f),
76 time_increment(0.0f),
77 scan_time(0.0f),
78 range_min(0.0f),
79 range_max(0.0f),
80 ranges(),
81 intensities()
82 {
83 }
84
85 void clear()
86 {
87 // *** header ***
88 header.clear();
89
90 // *** angle_min ***
91 angle_min = 0.0f;
92
93 // *** angle_max ***
94 angle_max = 0.0f;
95
96 // *** angle_increment ***
97 angle_increment = 0.0f;
98
99 // *** time_increment ***
100 time_increment = 0.0f;
101
102 // *** scan_time ***
103 scan_time = 0.0f;
104
105 // *** range_min ***
106 range_min = 0.0f;
107
108 // *** range_max ***
109 range_max = 0.0f;
110
111 // *** ranges ***
112 ranges.clear();
113
114 // *** intensities ***
115 intensities.clear();
116 }
117
118 bool readBare(yarp::os::ConnectionReader& connection) override
119 {
120 // *** header ***
121 if (!header.read(connection)) {
122 return false;
123 }
124
125 // *** angle_min ***
126 angle_min = connection.expectFloat32();
127
128 // *** angle_max ***
129 angle_max = connection.expectFloat32();
130
131 // *** angle_increment ***
132 angle_increment = connection.expectFloat32();
133
134 // *** time_increment ***
135 time_increment = connection.expectFloat32();
136
137 // *** scan_time ***
138 scan_time = connection.expectFloat32();
139
140 // *** range_min ***
141 range_min = connection.expectFloat32();
142
143 // *** range_max ***
144 range_max = connection.expectFloat32();
145
146 // *** ranges ***
147 int len = connection.expectInt32();
148 ranges.resize(len);
149 for (int i=0; i<len; i++) {
150 if (!ranges[i].read(connection)) {
151 return false;
152 }
153 }
154
155 // *** intensities ***
156 len = connection.expectInt32();
157 intensities.resize(len);
158 for (int i=0; i<len; i++) {
159 if (!intensities[i].read(connection)) {
160 return false;
161 }
162 }
163
164 return !connection.isError();
165 }
166
167 bool readBottle(yarp::os::ConnectionReader& connection) override
168 {
169 connection.convertTextMode();
170 yarp::os::idl::WireReader reader(connection);
171 if (!reader.readListHeader(10)) {
172 return false;
173 }
174
175 // *** header ***
176 if (!header.read(connection)) {
177 return false;
178 }
179
180 // *** angle_min ***
181 angle_min = reader.expectFloat32();
182
183 // *** angle_max ***
184 angle_max = reader.expectFloat32();
185
186 // *** angle_increment ***
187 angle_increment = reader.expectFloat32();
188
189 // *** time_increment ***
190 time_increment = reader.expectFloat32();
191
192 // *** scan_time ***
193 scan_time = reader.expectFloat32();
194
195 // *** range_min ***
196 range_min = reader.expectFloat32();
197
198 // *** range_max ***
199 range_max = reader.expectFloat32();
200
201 // *** ranges ***
202 if (connection.expectInt32() != BOTTLE_TAG_LIST) {
203 return false;
204 }
205 int len = connection.expectInt32();
206 ranges.resize(len);
207 for (int i=0; i<len; i++) {
208 if (!ranges[i].read(connection)) {
209 return false;
210 }
211 }
212
213 // *** intensities ***
214 if (connection.expectInt32() != BOTTLE_TAG_LIST) {
215 return false;
216 }
217 len = connection.expectInt32();
218 intensities.resize(len);
219 for (int i=0; i<len; i++) {
220 if (!intensities[i].read(connection)) {
221 return false;
222 }
223 }
224
225 return !connection.isError();
226 }
227
229 bool read(yarp::os::ConnectionReader& connection) override
230 {
231 return (connection.isBareMode() ? readBare(connection)
232 : readBottle(connection));
233 }
234
235 bool writeBare(yarp::os::ConnectionWriter& connection) const override
236 {
237 // *** header ***
238 if (!header.write(connection)) {
239 return false;
240 }
241
242 // *** angle_min ***
243 connection.appendFloat32(angle_min);
244
245 // *** angle_max ***
246 connection.appendFloat32(angle_max);
247
248 // *** angle_increment ***
249 connection.appendFloat32(angle_increment);
250
251 // *** time_increment ***
252 connection.appendFloat32(time_increment);
253
254 // *** scan_time ***
255 connection.appendFloat32(scan_time);
256
257 // *** range_min ***
258 connection.appendFloat32(range_min);
259
260 // *** range_max ***
261 connection.appendFloat32(range_max);
262
263 // *** ranges ***
264 connection.appendInt32(ranges.size());
265 for (size_t i=0; i<ranges.size(); i++) {
266 if (!ranges[i].write(connection)) {
267 return false;
268 }
269 }
270
271 // *** intensities ***
272 connection.appendInt32(intensities.size());
273 for (size_t i=0; i<intensities.size(); i++) {
274 if (!intensities[i].write(connection)) {
275 return false;
276 }
277 }
278
279 return !connection.isError();
280 }
281
282 bool writeBottle(yarp::os::ConnectionWriter& connection) const override
283 {
284 connection.appendInt32(BOTTLE_TAG_LIST);
285 connection.appendInt32(10);
286
287 // *** header ***
288 if (!header.write(connection)) {
289 return false;
290 }
291
292 // *** angle_min ***
294 connection.appendFloat32(angle_min);
295
296 // *** angle_max ***
298 connection.appendFloat32(angle_max);
299
300 // *** angle_increment ***
302 connection.appendFloat32(angle_increment);
303
304 // *** time_increment ***
306 connection.appendFloat32(time_increment);
307
308 // *** scan_time ***
310 connection.appendFloat32(scan_time);
311
312 // *** range_min ***
314 connection.appendFloat32(range_min);
315
316 // *** range_max ***
318 connection.appendFloat32(range_max);
319
320 // *** ranges ***
321 connection.appendInt32(BOTTLE_TAG_LIST);
322 connection.appendInt32(ranges.size());
323 for (size_t i=0; i<ranges.size(); i++) {
324 if (!ranges[i].write(connection)) {
325 return false;
326 }
327 }
328
329 // *** intensities ***
330 connection.appendInt32(BOTTLE_TAG_LIST);
331 connection.appendInt32(intensities.size());
332 for (size_t i=0; i<intensities.size(); i++) {
333 if (!intensities[i].write(connection)) {
334 return false;
335 }
336 }
337
338 connection.convertTextMode();
339 return !connection.isError();
340 }
341
343 bool write(yarp::os::ConnectionWriter& connection) const override
344 {
345 return (connection.isBareMode() ? writeBare(connection)
346 : writeBottle(connection));
347 }
348
349 // This class will serialize ROS style or YARP style depending on protocol.
350 // If you need to force a serialization style, use one of these classes:
353
354 // The name for this message, ROS will need this
355 static constexpr const char* typeName = "sensor_msgs/MultiEchoLaserScan";
356
357 // The checksum for this message, ROS will need this
358 static constexpr const char* typeChecksum = "6fefb0c6da89d7c8abe4b339f5c2f8fb";
359
360 // The source text for this message, ROS will need this
361 static constexpr const char* typeText = "\
362# Single scan from a multi-echo planar laser range-finder\n\
363#\n\
364# If you have another ranging device with different behavior (e.g. a sonar\n\
365# array), please find or create a different message, since applications\n\
366# will make fairly laser-specific assumptions about this data\n\
367\n\
368Header header # timestamp in the header is the acquisition time of \n\
369 # the first ray in the scan.\n\
370 #\n\
371 # in frame frame_id, angles are measured around \n\
372 # the positive Z axis (counterclockwise, if Z is up)\n\
373 # with zero angle being forward along the x axis\n\
374 \n\
375float32 angle_min # start angle of the scan [rad]\n\
376float32 angle_max # end angle of the scan [rad]\n\
377float32 angle_increment # angular distance between measurements [rad]\n\
378\n\
379float32 time_increment # time between measurements [seconds] - if your scanner\n\
380 # is moving, this will be used in interpolating position\n\
381 # of 3d points\n\
382float32 scan_time # time between scans [seconds]\n\
383\n\
384float32 range_min # minimum range value [m]\n\
385float32 range_max # maximum range value [m]\n\
386\n\
387LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded)\n\
388 # +Inf measurements are out of range\n\
389 # -Inf measurements are too close to determine exact distance.\n\
390LaserEcho[] intensities # intensity data [device-specific units]. If your\n\
391 # device does not provide intensities, please leave\n\
392 # the array empty.\n\
393================================================================================\n\
394MSG: std_msgs/Header\n\
395# Standard metadata for higher-level stamped data types.\n\
396# This is generally used to communicate timestamped data \n\
397# in a particular coordinate frame.\n\
398# \n\
399# sequence ID: consecutively increasing ID \n\
400uint32 seq\n\
401#Two-integer timestamp that is expressed as:\n\
402# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
403# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
404# time-handling sugar is provided by the client library\n\
405time stamp\n\
406#Frame this data is associated with\n\
407# 0: no frame\n\
408# 1: global frame\n\
409string frame_id\n\
410\n\
411================================================================================\n\
412MSG: sensor_msgs/LaserEcho\n\
413# This message is a submessage of MultiEchoLaserScan and is not intended\n\
414# to be used separately.\n\
415\n\
416float32[] echoes # Multiple values of ranges or intensities.\n\
417 # Each array represents data from the same angle increment.\n\
418";
419
420 yarp::os::Type getType() const override
421 {
422 yarp::os::Type typ = yarp::os::Type::byName(typeName, typeName);
423 typ.addProperty("md5sum", yarp::os::Value(typeChecksum));
424 typ.addProperty("message_definition", yarp::os::Value(typeText));
425 return typ;
426 }
427};
428
429} // namespace sensor_msgs
430} // namespace rosmsg
431} // namespace yarp
432
433#endif // YARP_ROSMSG_sensor_msgs_MultiEchoLaserScan_h
#define BOTTLE_TAG_LIST
Definition: Bottle.h:28
#define BOTTLE_TAG_FLOAT32
Definition: Bottle.h:24
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 yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
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 void appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number to the network connection.
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:43
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
Definition: WirePortable.h:21
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:27
yarp::conf::float32_t expectFloat32()
Definition: WireReader.h:103
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
yarp::rosmsg::sensor_msgs::MultiEchoLaserScan MultiEchoLaserScan
float float32_t
Definition: numeric.h:76
bool read(ImageOf< PixelRgb > &dest, const std::string &src, image_fileformat format=FORMAT_ANY)
Definition: ImageFile.cpp:915
bool write(const ImageOf< PixelRgb > &src, const std::string &dest, image_fileformat format=FORMAT_PPM)
Definition: ImageFile.cpp:1091
The main, catch-all namespace for YARP.
Definition: dirs.h:16