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