42#ifndef YARP_ROSMSG_sensor_msgs_MultiEchoLaserScan_h
43#define YARP_ROSMSG_sensor_msgs_MultiEchoLaserScan_h
68 std::vector<yarp::rosmsg::sensor_msgs::LaserEcho> ranges;
69 std::vector<yarp::rosmsg::sensor_msgs::LaserEcho> intensities;
75 angle_increment(0.0f),
97 angle_increment = 0.0f;
100 time_increment = 0.0f;
121 if (!header.
read(connection)) {
149 for (
int i=0; i<len; i++) {
150 if (!ranges[i].
read(connection)) {
157 intensities.resize(len);
158 for (
int i=0; i<len; i++) {
159 if (!intensities[i].
read(connection)) {
176 if (!header.
read(connection)) {
207 for (
int i=0; i<len; i++) {
208 if (!ranges[i].
read(connection)) {
218 intensities.resize(len);
219 for (
int i=0; i<len; i++) {
220 if (!intensities[i].
read(connection)) {
231 return (connection.
isBareMode() ? readBare(connection)
232 : readBottle(connection));
238 if (!header.
write(connection)) {
265 for (
size_t i=0; i<ranges.size(); i++) {
266 if (!ranges[i].
write(connection)) {
273 for (
size_t i=0; i<intensities.size(); i++) {
274 if (!intensities[i].
write(connection)) {
288 if (!header.
write(connection)) {
323 for (
size_t i=0; i<ranges.size(); i++) {
324 if (!ranges[i].
write(connection)) {
332 for (
size_t i=0; i<intensities.size(); i++) {
333 if (!intensities[i].
write(connection)) {
345 return (connection.
isBareMode() ? writeBare(connection)
346 : writeBottle(connection));
355 static constexpr const char* typeName =
"sensor_msgs/MultiEchoLaserScan";
358 static constexpr const char* typeChecksum =
"6fefb0c6da89d7c8abe4b339f5c2f8fb";
361 static constexpr const char* typeText =
"\
362# Single scan from a multi-echo planar laser range-finder\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\
368Header header # timestamp in the header is the acquisition time of \n\
369 # the first ray in the scan.\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\
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\
379float32 time_increment # time between measurements [seconds] - if your scanner\n\
380 # is moving, this will be used in interpolating position\n\
382float32 scan_time # time between scans [seconds]\n\
384float32 range_min # minimum range value [m]\n\
385float32 range_max # maximum range value [m]\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\
399# sequence ID: consecutively increasing ID \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\
406#Frame this data is associated with\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\
416float32[] echoes # Multiple values of ranges or intensities.\n\
417 # Each array represents data from the same angle increment.\n\
#define BOTTLE_TAG_FLOAT32
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)
Type & addProperty(const char *key, const Value &val)
A single value (typically within a Bottle).
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool write(const yarp::os::idl::WireWriter &writer) const
IDL-friendly connection reader.
yarp::conf::float32_t expectFloat32()
yarp::rosmsg::sensor_msgs::MultiEchoLaserScan MultiEchoLaserScan
bool read(ImageOf< PixelRgb > &dest, const std::string &src, image_fileformat format=FORMAT_ANY)
bool write(const ImageOf< PixelRgb > &src, const std::string &dest, image_fileformat format=FORMAT_PPM)
The main, catch-all namespace for YARP.