|
YARP
Yet Another Robot Platform
|
|
Go to the documentation of this file.
54 #ifndef YARP_ROSMSG_sensor_msgs_Range_h
55 #define YARP_ROSMSG_sensor_msgs_Range_h
250 static constexpr
const char*
typeName =
"sensor_msgs/Range";
253 static constexpr
const char*
typeChecksum =
"c005c34273dc426c67a020a87bc24148";
257 # Single range reading from an active ranger that emits energy and reports\n\
258 # one range reading that is valid along an arc at the distance measured. \n\
259 # This message is not appropriate for laser scanners. See the LaserScan\n\
260 # message if you are working with a laser scanner.\n\
262 # This message also can represent a fixed-distance (binary) ranger. This\n\
263 # sensor will have min_range===max_range===distance of detection.\n\
264 # These sensors follow REP 117 and will output -Inf if the object is detected\n\
265 # and +Inf if the object is outside of the detection range.\n\
267 Header header # timestamp in the header is the time the ranger\n\
268 # returned the distance reading\n\
270 # Radiation type enums\n\
271 # If you want a value added to this list, send an email to the ros-users list\n\
272 uint8 ULTRASOUND=0\n\
275 uint8 radiation_type # the type of radiation used by the sensor\n\
276 # (sound, IR, etc) [enum]\n\
278 float32 field_of_view # the size of the arc that the distance reading is\n\
280 # the object causing the range reading may have\n\
281 # been anywhere within -field_of_view/2 and\n\
282 # field_of_view/2 at the measured range. \n\
283 # 0 angle corresponds to the x-axis of the sensor.\n\
285 float32 min_range # minimum range value [m]\n\
286 float32 max_range # maximum range value [m]\n\
287 # Fixed distance rangers require min_range==max_range\n\
289 float32 range # range data [m]\n\
290 # (Note: values < range_min or > range_max\n\
291 # should be discarded)\n\
292 # Fixed distance rangers only output -Inf or +Inf.\n\
293 # -Inf represents a detection within fixed distance.\n\
294 # (Detection too close to the sensor to quantify)\n\
295 # +Inf represents no detection within the fixed distance.\n\
296 # (Object out of range)\n\
297 ================================================================================\n\
298 MSG: std_msgs/Header\n\
299 # Standard metadata for higher-level stamped data types.\n\
300 # This is generally used to communicate timestamped data \n\
301 # in a particular coordinate frame.\n\
303 # sequence ID: consecutively increasing ID \n\
305 #Two-integer timestamp that is expressed as:\n\
306 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
307 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
308 # time-handling sugar is provided by the client library\n\
310 #Frame this data is associated with\n\
329 #endif // YARP_ROSMSG_sensor_msgs_Range_h
virtual void appendFloat32(yarp::conf::float32_t data)=0
Send a representation of a 32-bit floating point number to the network connection.
static constexpr const char * typeText
yarp::os::idl::BottleStyle< yarp::rosmsg::sensor_msgs::Range > bottleStyle
yarp::conf::float32_t expectFloat32()
yarp::rosmsg::std_msgs::Header header
virtual bool read(yarp::os::idl::WireReader &reader)
yarp::conf::float32_t field_of_view
virtual void appendInt8(std::int8_t data)=0
Send a representation of a 8-bit integer to the network connection.
virtual bool isBareMode() const =0
Check if the connection is bare mode.
static constexpr const char * typeName
static const std::uint8_t ULTRASOUND
bool writeBare(yarp::os::ConnectionWriter &connection) const override
virtual std::int8_t expectInt8()=0
Read a 8-bit integer from the network connection.
yarp::conf::float32_t range
bool write(yarp::os::ConnectionWriter &connection) const override
Write this object to a network connection.
virtual bool isError() const =0
#define BOTTLE_TAG_FLOAT32
static Type byName(const char *name)
bool writeBottle(yarp::os::ConnectionWriter &connection) const override
Type & addProperty(const char *key, const Value &val)
std::uint8_t radiation_type
An interface for writing to a network connection.
virtual bool isError() const =0
virtual bool convertTextMode()=0
Reads in a standard description in text mode, and converts it to a standard description in binary.
static const std::uint8_t INFRARED
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.
yarp::os::idl::BareStyle< yarp::rosmsg::sensor_msgs::Range > rosStyle
virtual bool convertTextMode()=0
Converts a standard description in binary into a textual description, if the connection is in text-mo...
yarp::os::Type getType() const override
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 readBottle(yarp::os::ConnectionReader &connection) override
static constexpr const char * typeChecksum
The main, catch-all namespace for YARP.
virtual yarp::conf::float32_t expectFloat32()=0
Read a 32-bit floating point number from the network connection.
bool readBare(yarp::os::ConnectionReader &connection) override
yarp::conf::float32_t min_range
A single value (typically within a Bottle).
yarp::conf::float32_t max_range
bool read(yarp::os::ConnectionReader &connection) override
Read this object from a network connection.
virtual bool write(const yarp::os::idl::WireWriter &writer) const