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