41#ifndef YARP_ROSMSG_sensor_msgs_LaserScan_h
42#define YARP_ROSMSG_sensor_msgs_LaserScan_h
66 std::vector<yarp::conf::float32_t> ranges;
67 std::vector<yarp::conf::float32_t> intensities;
73 angle_increment(0.0f),
95 angle_increment = 0.0f;
98 time_increment = 0.0f;
119 if (!header.
read(connection)) {
153 intensities.resize(len);
170 if (!header.
read(connection)) {
201 for (
int i=0; i<len; i++) {
210 intensities.resize(len);
211 for (
int i=0; i<len; i++) {
221 return (connection.
isBareMode() ? readBare(connection)
222 : readBottle(connection));
228 if (!header.
write(connection)) {
255 if (ranges.size()>0) {
261 if (intensities.size()>0) {
274 if (!header.
write(connection)) {
309 for (
size_t i=0; i<ranges.size(); i++) {
316 for (
size_t i=0; i<intensities.size(); i++) {
327 return (connection.
isBareMode() ? writeBare(connection)
328 : writeBottle(connection));
337 static constexpr const char* typeName =
"sensor_msgs/LaserScan";
340 static constexpr const char* typeChecksum =
"90c7ef2dc6895d81024acba2ac42f369";
343 static constexpr const char* typeText =
"\
344# Single scan from a planar laser range-finder\n\
346# If you have another ranging device with different behavior (e.g. a sonar\n\
347# array), please find or create a different message, since applications\n\
348# will make fairly laser-specific assumptions about this data\n\
350Header header # timestamp in the header is the acquisition time of \n\
351 # the first ray in the scan.\n\
353 # in frame frame_id, angles are measured around \n\
354 # the positive Z axis (counterclockwise, if Z is up)\n\
355 # with zero angle being forward along the x axis\n\
357float32 angle_min # start angle of the scan [rad]\n\
358float32 angle_max # end angle of the scan [rad]\n\
359float32 angle_increment # angular distance between measurements [rad]\n\
361float32 time_increment # time between measurements [seconds] - if your scanner\n\
362 # is moving, this will be used in interpolating position\n\
364float32 scan_time # time between scans [seconds]\n\
366float32 range_min # minimum range value [m]\n\
367float32 range_max # maximum range value [m]\n\
369float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)\n\
370float32[] intensities # intensity data [device-specific units]. If your\n\
371 # device does not provide intensities, please leave\n\
372 # the array empty.\n\
374================================================================================\n\
375MSG: std_msgs/Header\n\
376# Standard metadata for higher-level stamped data types.\n\
377# This is generally used to communicate timestamped data \n\
378# in a particular coordinate frame.\n\
380# sequence ID: consecutively increasing ID \n\
382#Two-integer timestamp that is expressed as:\n\
383# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
384# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
385# time-handling sugar is provided by the client library\n\
387#Frame this data is associated with\n\
#define BOTTLE_TAG_FLOAT32
An interface for reading from a network connection.
virtual bool expectBlock(char *data, size_t len)=0
Read a block of data from the 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 void appendExternalBlock(const char *data, size_t len)=0
Send a block of data to the network connection, without making a copy.
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::LaserScan LaserScan
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.