|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
44 #ifndef YARP_ROSMSG_sensor_msgs_LaserScan_h
45 #define YARP_ROSMSG_sensor_msgs_LaserScan_h
69 std::vector<yarp::conf::float32_t>
ranges;
204 for (
int i=0; i<len; i++) {
214 for (
int i=0; i<len; i++) {
312 for (
size_t i=0; i<
ranges.size(); i++) {
340 static constexpr
const char*
typeName =
"sensor_msgs/LaserScan";
343 static constexpr
const char*
typeChecksum =
"90c7ef2dc6895d81024acba2ac42f369";
347 # Single scan from a planar laser range-finder\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\
353 Header header # timestamp in the header is the acquisition time of \n\
354 # the first ray in the scan.\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\
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\
364 float32 time_increment # time between measurements [seconds] - if your scanner\n\
365 # is moving, this will be used in interpolating position\n\
367 float32 scan_time # time between scans [seconds]\n\
369 float32 range_min # minimum range value [m]\n\
370 float32 range_max # maximum range value [m]\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\
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\
383 # sequence ID: consecutively increasing ID \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\
390 #Frame this data is associated with\n\
409 #endif // YARP_ROSMSG_sensor_msgs_LaserScan_h
virtual void appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number to the network connection.
bool writeBare(yarp::os::ConnectionWriter &connection) const override
yarp::conf::float32_t expectFloat32()
virtual bool read(yarp::os::idl::WireReader &reader)
yarp::conf::float32_t time_increment
virtual bool isBareMode() const =0
Check if the connection is bare mode.
yarp::conf::float32_t scan_time
yarp::os::Type getType() const override
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
static constexpr const char * typeChecksum
virtual bool isError() const =0
#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::conf::float32_t angle_max
Type & addProperty(const char *key, const Value &val)
An interface for writing to a network connection.
yarp::rosmsg::std_msgs::Header header
virtual bool isError() const =0
yarp::conf::float32_t range_max
bool writeBottle(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.
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::LaserScan > rosStyle
A "tamed" Portable, that promises to serialize itself in an IDL-friendly way.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
std::vector< yarp::conf::float32_t > ranges
yarp::conf::float32_t angle_increment
std::vector< yarp::conf::float32_t > intensities
yarp::conf::float32_t range_min
static constexpr const char * typeText
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.
bool readBare(yarp::os::ConnectionReader &connection) override
The main, catch-all namespace for YARP.
static constexpr const char * typeName
virtual yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
yarp::conf::float32_t angle_min
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::LaserScan > bottleStyle
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 expectBlock(char *data, size_t len)=0
Read a block of data from the network connection.
A single value (typically within a Bottle).
bool readBottle(yarp::os::ConnectionReader &connection) override
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