00001
00002 #ifndef SENSOR_MSGS_MESSAGE_RANGE_H
00003 #define SENSOR_MSGS_MESSAGE_RANGE_H
00004 #include <string>
00005 #include <vector>
00006 #include <ostream>
00007 #include "ros/serialization.h"
00008 #include "ros/builtin_message_traits.h"
00009 #include "ros/message_operations.h"
00010 #include "ros/message.h"
00011 #include "ros/time.h"
00012
00013 #include "std_msgs/Header.h"
00014
00015 namespace sensor_msgs
00016 {
00017 template <class ContainerAllocator>
00018 struct Range_ : public ros::Message
00019 {
00020 typedef Range_<ContainerAllocator> Type;
00021
00022 Range_()
00023 : header()
00024 , radiation_type(0)
00025 , field_of_view(0.0)
00026 , min_range(0.0)
00027 , max_range(0.0)
00028 , range(0.0)
00029 {
00030 }
00031
00032 Range_(const ContainerAllocator& _alloc)
00033 : header(_alloc)
00034 , radiation_type(0)
00035 , field_of_view(0.0)
00036 , min_range(0.0)
00037 , max_range(0.0)
00038 , range(0.0)
00039 {
00040 }
00041
00042 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00043 ::std_msgs::Header_<ContainerAllocator> header;
00044
00045 typedef uint8_t _radiation_type_type;
00046 uint8_t radiation_type;
00047
00048 typedef float _field_of_view_type;
00049 float field_of_view;
00050
00051 typedef float _min_range_type;
00052 float min_range;
00053
00054 typedef float _max_range_type;
00055 float max_range;
00056
00057 typedef float _range_type;
00058 float range;
00059
00060 enum { ULTRASOUND = 0 };
00061 enum { INFRARED = 1 };
00062
00063 private:
00064 static const char* __s_getDataType_() { return "sensor_msgs/Range"; }
00065 public:
00066 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00067
00068 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00069
00070 private:
00071 static const char* __s_getMD5Sum_() { return "c005c34273dc426c67a020a87bc24148"; }
00072 public:
00073 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00074
00075 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00076
00077 private:
00078 static const char* __s_getMessageDefinition_() { return "# Single range reading from an active ranger that emits energy and reports\n\
00079 # one range reading that is valid along an arc at the distance measured. \n\
00080 # This message is not appropriate for fixed-range obstacle detectors, \n\
00081 # such as the Sharp GP2D15. This message is also not appropriate for laser \n\
00082 # scanners. See the LaserScan message if you are working with a laser scanner.\n\
00083 \n\
00084 Header header # timestamp in the header is the time the ranger\n\
00085 # returned the distance reading\n\
00086 \n\
00087 # Radiation type enums\n\
00088 # If you want a value added to this list, send an email to the ros-users list\n\
00089 uint8 ULTRASOUND=0\n\
00090 uint8 INFRARED=1\n\
00091 \n\
00092 uint8 radiation_type # the type of radiation used by the sensor\n\
00093 # (sound, IR, etc) [enum]\n\
00094 \n\
00095 float32 field_of_view # the size of the arc that the distance reading is\n\
00096 # valid for [rad]\n\
00097 # the object causing the range reading may have\n\
00098 # been anywhere within -field_of_view/2 and\n\
00099 # field_of_view/2 at the measured range. \n\
00100 # 0 angle corresponds to the x-axis of the sensor.\n\
00101 \n\
00102 float32 min_range # minimum range value [m]\n\
00103 float32 max_range # maximum range value [m]\n\
00104 \n\
00105 float32 range # range data [m]\n\
00106 # (Note: values < range_min or > range_max\n\
00107 # should be discarded)\n\
00108 \n\
00109 ================================================================================\n\
00110 MSG: std_msgs/Header\n\
00111 # Standard metadata for higher-level stamped data types.\n\
00112 # This is generally used to communicate timestamped data \n\
00113 # in a particular coordinate frame.\n\
00114 # \n\
00115 # sequence ID: consecutively increasing ID \n\
00116 uint32 seq\n\
00117 #Two-integer timestamp that is expressed as:\n\
00118 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00119 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00120 # time-handling sugar is provided by the client library\n\
00121 time stamp\n\
00122 #Frame this data is associated with\n\
00123 # 0: no frame\n\
00124 # 1: global frame\n\
00125 string frame_id\n\
00126 \n\
00127 "; }
00128 public:
00129 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00130
00131 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00132
00133 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00134 {
00135 ros::serialization::OStream stream(write_ptr, 1000000000);
00136 ros::serialization::serialize(stream, header);
00137 ros::serialization::serialize(stream, radiation_type);
00138 ros::serialization::serialize(stream, field_of_view);
00139 ros::serialization::serialize(stream, min_range);
00140 ros::serialization::serialize(stream, max_range);
00141 ros::serialization::serialize(stream, range);
00142 return stream.getData();
00143 }
00144
00145 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00146 {
00147 ros::serialization::IStream stream(read_ptr, 1000000000);
00148 ros::serialization::deserialize(stream, header);
00149 ros::serialization::deserialize(stream, radiation_type);
00150 ros::serialization::deserialize(stream, field_of_view);
00151 ros::serialization::deserialize(stream, min_range);
00152 ros::serialization::deserialize(stream, max_range);
00153 ros::serialization::deserialize(stream, range);
00154 return stream.getData();
00155 }
00156
00157 ROS_DEPRECATED virtual uint32_t serializationLength() const
00158 {
00159 uint32_t size = 0;
00160 size += ros::serialization::serializationLength(header);
00161 size += ros::serialization::serializationLength(radiation_type);
00162 size += ros::serialization::serializationLength(field_of_view);
00163 size += ros::serialization::serializationLength(min_range);
00164 size += ros::serialization::serializationLength(max_range);
00165 size += ros::serialization::serializationLength(range);
00166 return size;
00167 }
00168
00169 typedef boost::shared_ptr< ::sensor_msgs::Range_<ContainerAllocator> > Ptr;
00170 typedef boost::shared_ptr< ::sensor_msgs::Range_<ContainerAllocator> const> ConstPtr;
00171 };
00172 typedef ::sensor_msgs::Range_<std::allocator<void> > Range;
00173
00174 typedef boost::shared_ptr< ::sensor_msgs::Range> RangePtr;
00175 typedef boost::shared_ptr< ::sensor_msgs::Range const> RangeConstPtr;
00176
00177
00178 template<typename ContainerAllocator>
00179 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Range_<ContainerAllocator> & v)
00180 {
00181 ros::message_operations::Printer< ::sensor_msgs::Range_<ContainerAllocator> >::stream(s, "", v);
00182 return s;}
00183
00184 }
00185
00186 namespace ros
00187 {
00188 namespace message_traits
00189 {
00190 template<class ContainerAllocator>
00191 struct MD5Sum< ::sensor_msgs::Range_<ContainerAllocator> > {
00192 static const char* value()
00193 {
00194 return "c005c34273dc426c67a020a87bc24148";
00195 }
00196
00197 static const char* value(const ::sensor_msgs::Range_<ContainerAllocator> &) { return value(); }
00198 static const uint64_t static_value1 = 0xc005c34273dc426cULL;
00199 static const uint64_t static_value2 = 0x67a020a87bc24148ULL;
00200 };
00201
00202 template<class ContainerAllocator>
00203 struct DataType< ::sensor_msgs::Range_<ContainerAllocator> > {
00204 static const char* value()
00205 {
00206 return "sensor_msgs/Range";
00207 }
00208
00209 static const char* value(const ::sensor_msgs::Range_<ContainerAllocator> &) { return value(); }
00210 };
00211
00212 template<class ContainerAllocator>
00213 struct Definition< ::sensor_msgs::Range_<ContainerAllocator> > {
00214 static const char* value()
00215 {
00216 return "# Single range reading from an active ranger that emits energy and reports\n\
00217 # one range reading that is valid along an arc at the distance measured. \n\
00218 # This message is not appropriate for fixed-range obstacle detectors, \n\
00219 # such as the Sharp GP2D15. This message is also not appropriate for laser \n\
00220 # scanners. See the LaserScan message if you are working with a laser scanner.\n\
00221 \n\
00222 Header header # timestamp in the header is the time the ranger\n\
00223 # returned the distance reading\n\
00224 \n\
00225 # Radiation type enums\n\
00226 # If you want a value added to this list, send an email to the ros-users list\n\
00227 uint8 ULTRASOUND=0\n\
00228 uint8 INFRARED=1\n\
00229 \n\
00230 uint8 radiation_type # the type of radiation used by the sensor\n\
00231 # (sound, IR, etc) [enum]\n\
00232 \n\
00233 float32 field_of_view # the size of the arc that the distance reading is\n\
00234 # valid for [rad]\n\
00235 # the object causing the range reading may have\n\
00236 # been anywhere within -field_of_view/2 and\n\
00237 # field_of_view/2 at the measured range. \n\
00238 # 0 angle corresponds to the x-axis of the sensor.\n\
00239 \n\
00240 float32 min_range # minimum range value [m]\n\
00241 float32 max_range # maximum range value [m]\n\
00242 \n\
00243 float32 range # range data [m]\n\
00244 # (Note: values < range_min or > range_max\n\
00245 # should be discarded)\n\
00246 \n\
00247 ================================================================================\n\
00248 MSG: std_msgs/Header\n\
00249 # Standard metadata for higher-level stamped data types.\n\
00250 # This is generally used to communicate timestamped data \n\
00251 # in a particular coordinate frame.\n\
00252 # \n\
00253 # sequence ID: consecutively increasing ID \n\
00254 uint32 seq\n\
00255 #Two-integer timestamp that is expressed as:\n\
00256 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00257 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00258 # time-handling sugar is provided by the client library\n\
00259 time stamp\n\
00260 #Frame this data is associated with\n\
00261 # 0: no frame\n\
00262 # 1: global frame\n\
00263 string frame_id\n\
00264 \n\
00265 ";
00266 }
00267
00268 static const char* value(const ::sensor_msgs::Range_<ContainerAllocator> &) { return value(); }
00269 };
00270
00271 template<class ContainerAllocator> struct HasHeader< ::sensor_msgs::Range_<ContainerAllocator> > : public TrueType {};
00272 template<class ContainerAllocator> struct HasHeader< const ::sensor_msgs::Range_<ContainerAllocator> > : public TrueType {};
00273 }
00274 }
00275
00276 namespace ros
00277 {
00278 namespace serialization
00279 {
00280
00281 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::Range_<ContainerAllocator> >
00282 {
00283 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00284 {
00285 stream.next(m.header);
00286 stream.next(m.radiation_type);
00287 stream.next(m.field_of_view);
00288 stream.next(m.min_range);
00289 stream.next(m.max_range);
00290 stream.next(m.range);
00291 }
00292
00293 ROS_DECLARE_ALLINONE_SERIALIZER;
00294 };
00295 }
00296 }
00297
00298 namespace ros
00299 {
00300 namespace message_operations
00301 {
00302
00303 template<class ContainerAllocator>
00304 struct Printer< ::sensor_msgs::Range_<ContainerAllocator> >
00305 {
00306 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Range_<ContainerAllocator> & v)
00307 {
00308 s << indent << "header: ";
00309 s << std::endl;
00310 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00311 s << indent << "radiation_type: ";
00312 Printer<uint8_t>::stream(s, indent + " ", v.radiation_type);
00313 s << indent << "field_of_view: ";
00314 Printer<float>::stream(s, indent + " ", v.field_of_view);
00315 s << indent << "min_range: ";
00316 Printer<float>::stream(s, indent + " ", v.min_range);
00317 s << indent << "max_range: ";
00318 Printer<float>::stream(s, indent + " ", v.max_range);
00319 s << indent << "range: ";
00320 Printer<float>::stream(s, indent + " ", v.range);
00321 }
00322 };
00323
00324
00325 }
00326 }
00327
00328 #endif // SENSOR_MSGS_MESSAGE_RANGE_H
00329