|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
45 #ifndef YARP_ROSMSG_sensor_msgs_MultiEchoLaserScan_h
46 #define YARP_ROSMSG_sensor_msgs_MultiEchoLaserScan_h
71 std::vector<yarp::rosmsg::sensor_msgs::LaserEcho>
ranges;
72 std::vector<yarp::rosmsg::sensor_msgs::LaserEcho>
intensities;
152 for (
int i=0; i<len; i++) {
161 for (
int i=0; i<len; i++) {
210 for (
int i=0; i<len; i++) {
222 for (
int i=0; i<len; i++) {
268 for (
size_t i=0; i<
ranges.size(); i++) {
326 for (
size_t i=0; i<
ranges.size(); i++) {
358 static constexpr
const char*
typeName =
"sensor_msgs/MultiEchoLaserScan";
361 static constexpr
const char*
typeChecksum =
"6fefb0c6da89d7c8abe4b339f5c2f8fb";
365 # Single scan from a multi-echo planar laser range-finder\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\
371 Header header # timestamp in the header is the acquisition time of \n\
372 # the first ray in the scan.\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\
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\
382 float32 time_increment # time between measurements [seconds] - if your scanner\n\
383 # is moving, this will be used in interpolating position\n\
385 float32 scan_time # time between scans [seconds]\n\
387 float32 range_min # minimum range value [m]\n\
388 float32 range_max # maximum range value [m]\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\
402 # sequence ID: consecutively increasing ID \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\
409 #Frame this data is associated with\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\
419 float32[] echoes # Multiple values of ranges or intensities.\n\
420 # Each array represents data from the same angle increment.\n\
436 #endif // YARP_ROSMSG_sensor_msgs_MultiEchoLaserScan_h
virtual void appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number to the network connection.
yarp::conf::float32_t scan_time
yarp::conf::float32_t expectFloat32()
yarp::conf::float32_t range_min
virtual bool read(yarp::os::idl::WireReader &reader)
virtual bool isBareMode() const =0
Check if the connection is bare mode.
static constexpr const char * typeText
static constexpr const char * typeChecksum
std::vector< yarp::rosmsg::sensor_msgs::LaserEcho > intensities
yarp::conf::float32_t angle_max
yarp::conf::float32_t angle_min
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::MultiEchoLaserScan > rosStyle
virtual bool isError() const =0
yarp::conf::float32_t range_max
#define BOTTLE_TAG_FLOAT32
static Type byName(const char *name)
virtual std::int32_t expectInt32()=0
Read a 32-bit integer from the network connection.
yarp::rosmsg::std_msgs::Header header
Type & addProperty(const char *key, const Value &val)
yarp::conf::float32_t time_increment
bool readBottle(yarp::os::ConnectionReader &connection) override
An interface for writing to a network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
virtual bool isError() const =0
bool writeBare(yarp::os::ConnectionWriter &connection) const override
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::os::Type getType() const override
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.
IDL-friendly connection reader.
An interface for reading from a network connection.
The main, catch-all namespace for YARP.
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
yarp::conf::float32_t angle_increment
virtual yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
static constexpr const char * typeName
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::MultiEchoLaserScan > bottleStyle
A single value (typically within a Bottle).
std::vector< yarp::rosmsg::sensor_msgs::LaserEcho > ranges
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
virtual bool write(const yarp::os::idl::WireWriter &writer) const