51#ifndef YARP_ROSMSG_sensor_msgs_Range_h
52#define YARP_ROSMSG_sensor_msgs_Range_h
69 static const std::uint8_t ULTRASOUND = 0;
70 static const std::uint8_t INFRARED = 1;
71 std::uint8_t radiation_type;
100 field_of_view = 0.0f;
115 if (!header.
read(connection)) {
146 if (!header.
read(connection)) {
171 return (connection.
isBareMode() ? readBare(connection)
172 : readBottle(connection));
178 if (!header.
write(connection)) {
206 if (!header.
write(connection)) {
237 return (connection.
isBareMode() ? writeBare(connection)
238 : writeBottle(connection));
247 static constexpr const char* typeName =
"sensor_msgs/Range";
250 static constexpr const char* typeChecksum =
"c005c34273dc426c67a020a87bc24148";
253 static constexpr const char* typeText =
"\
254# Single range reading from an active ranger that emits energy and reports\n\
255# one range reading that is valid along an arc at the distance measured. \n\
256# This message is not appropriate for laser scanners. See the LaserScan\n\
257# message if you are working with a laser scanner.\n\
259# This message also can represent a fixed-distance (binary) ranger. This\n\
260# sensor will have min_range===max_range===distance of detection.\n\
261# These sensors follow REP 117 and will output -Inf if the object is detected\n\
262# and +Inf if the object is outside of the detection range.\n\
264Header header # timestamp in the header is the time the ranger\n\
265 # returned the distance reading\n\
267# Radiation type enums\n\
268# If you want a value added to this list, send an email to the ros-users list\n\
272uint8 radiation_type # the type of radiation used by the sensor\n\
273 # (sound, IR, etc) [enum]\n\
275float32 field_of_view # the size of the arc that the distance reading is\n\
277 # the object causing the range reading may have\n\
278 # been anywhere within -field_of_view/2 and\n\
279 # field_of_view/2 at the measured range. \n\
280 # 0 angle corresponds to the x-axis of the sensor.\n\
282float32 min_range # minimum range value [m]\n\
283float32 max_range # maximum range value [m]\n\
284 # Fixed distance rangers require min_range==max_range\n\
286float32 range # range data [m]\n\
287 # (Note: values < range_min or > range_max\n\
288 # should be discarded)\n\
289 # Fixed distance rangers only output -Inf or +Inf.\n\
290 # -Inf represents a detection within fixed distance.\n\
291 # (Detection too close to the sensor to quantify)\n\
292 # +Inf represents no detection within the fixed distance.\n\
293 # (Object out of range)\n\
294================================================================================\n\
295MSG: std_msgs/Header\n\
296# Standard metadata for higher-level stamped data types.\n\
297# This is generally used to communicate timestamped data \n\
298# in a particular coordinate frame.\n\
300# sequence ID: consecutively increasing ID \n\
302#Two-integer timestamp that is expressed as:\n\
303# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
304# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
305# time-handling sugar is provided by the client library\n\
307#Frame this data is associated with\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 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
virtual std::int8_t expectInt8()=0
Read a 8-bit integer from the network connection.
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 appendInt8(std::int8_t data)=0
Send a representation of a 8-bit integer to the network connection.
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::Range Range
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.