00001
00002 #ifndef SENSOR_MSGS_MESSAGE_LASERSCAN_H
00003 #define SENSOR_MSGS_MESSAGE_LASERSCAN_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 LaserScan_ : public ros::Message
00019 {
00020 typedef LaserScan_<ContainerAllocator> Type;
00021
00022 LaserScan_()
00023 : header()
00024 , angle_min(0.0)
00025 , angle_max(0.0)
00026 , angle_increment(0.0)
00027 , time_increment(0.0)
00028 , scan_time(0.0)
00029 , range_min(0.0)
00030 , range_max(0.0)
00031 , ranges()
00032 , intensities()
00033 {
00034 }
00035
00036 LaserScan_(const ContainerAllocator& _alloc)
00037 : header(_alloc)
00038 , angle_min(0.0)
00039 , angle_max(0.0)
00040 , angle_increment(0.0)
00041 , time_increment(0.0)
00042 , scan_time(0.0)
00043 , range_min(0.0)
00044 , range_max(0.0)
00045 , ranges(_alloc)
00046 , intensities(_alloc)
00047 {
00048 }
00049
00050 typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
00051 ::std_msgs::Header_<ContainerAllocator> header;
00052
00053 typedef float _angle_min_type;
00054 float angle_min;
00055
00056 typedef float _angle_max_type;
00057 float angle_max;
00058
00059 typedef float _angle_increment_type;
00060 float angle_increment;
00061
00062 typedef float _time_increment_type;
00063 float time_increment;
00064
00065 typedef float _scan_time_type;
00066 float scan_time;
00067
00068 typedef float _range_min_type;
00069 float range_min;
00070
00071 typedef float _range_max_type;
00072 float range_max;
00073
00074 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _ranges_type;
00075 std::vector<float, typename ContainerAllocator::template rebind<float>::other > ranges;
00076
00077 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _intensities_type;
00078 std::vector<float, typename ContainerAllocator::template rebind<float>::other > intensities;
00079
00080
00081 ROS_DEPRECATED uint32_t get_ranges_size() const { return (uint32_t)ranges.size(); }
00082 ROS_DEPRECATED void set_ranges_size(uint32_t size) { ranges.resize((size_t)size); }
00083 ROS_DEPRECATED void get_ranges_vec(std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) const { vec = this->ranges; }
00084 ROS_DEPRECATED void set_ranges_vec(const std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) { this->ranges = vec; }
00085 ROS_DEPRECATED uint32_t get_intensities_size() const { return (uint32_t)intensities.size(); }
00086 ROS_DEPRECATED void set_intensities_size(uint32_t size) { intensities.resize((size_t)size); }
00087 ROS_DEPRECATED void get_intensities_vec(std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) const { vec = this->intensities; }
00088 ROS_DEPRECATED void set_intensities_vec(const std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) { this->intensities = vec; }
00089 private:
00090 static const char* __s_getDataType_() { return "sensor_msgs/LaserScan"; }
00091 public:
00092 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); }
00093
00094 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); }
00095
00096 private:
00097 static const char* __s_getMD5Sum_() { return "90c7ef2dc6895d81024acba2ac42f369"; }
00098 public:
00099 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); }
00100
00101 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); }
00102
00103 private:
00104 static const char* __s_getMessageDefinition_() { return "# Single scan from a planar laser range-finder\n\
00105 #\n\
00106 # If you have another ranging device with different behavior (e.g. a sonar\n\
00107 # array), please find or create a different message, since applications\n\
00108 # will make fairly laser-specific assumptions about this data\n\
00109 \n\
00110 Header header # timestamp in the header is the acquisition time of \n\
00111 # the first ray in the scan.\n\
00112 #\n\
00113 # in frame frame_id, angles are measured around \n\
00114 # the positive Z axis (counterclockwise, if Z is up)\n\
00115 # with zero angle being forward along the x axis\n\
00116 \n\
00117 float32 angle_min # start angle of the scan [rad]\n\
00118 float32 angle_max # end angle of the scan [rad]\n\
00119 float32 angle_increment # angular distance between measurements [rad]\n\
00120 \n\
00121 float32 time_increment # time between measurements [seconds] - if your scanner\n\
00122 # is moving, this will be used in interpolating position\n\
00123 # of 3d points\n\
00124 float32 scan_time # time between scans [seconds]\n\
00125 \n\
00126 float32 range_min # minimum range value [m]\n\
00127 float32 range_max # maximum range value [m]\n\
00128 \n\
00129 float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)\n\
00130 float32[] intensities # intensity data [device-specific units]. If your\n\
00131 # device does not provide intensities, please leave\n\
00132 # the array empty.\n\
00133 \n\
00134 ================================================================================\n\
00135 MSG: std_msgs/Header\n\
00136 # Standard metadata for higher-level stamped data types.\n\
00137 # This is generally used to communicate timestamped data \n\
00138 # in a particular coordinate frame.\n\
00139 # \n\
00140 # sequence ID: consecutively increasing ID \n\
00141 uint32 seq\n\
00142 #Two-integer timestamp that is expressed as:\n\
00143 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00144 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00145 # time-handling sugar is provided by the client library\n\
00146 time stamp\n\
00147 #Frame this data is associated with\n\
00148 # 0: no frame\n\
00149 # 1: global frame\n\
00150 string frame_id\n\
00151 \n\
00152 "; }
00153 public:
00154 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); }
00155
00156 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); }
00157
00158 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const
00159 {
00160 ros::serialization::OStream stream(write_ptr, 1000000000);
00161 ros::serialization::serialize(stream, header);
00162 ros::serialization::serialize(stream, angle_min);
00163 ros::serialization::serialize(stream, angle_max);
00164 ros::serialization::serialize(stream, angle_increment);
00165 ros::serialization::serialize(stream, time_increment);
00166 ros::serialization::serialize(stream, scan_time);
00167 ros::serialization::serialize(stream, range_min);
00168 ros::serialization::serialize(stream, range_max);
00169 ros::serialization::serialize(stream, ranges);
00170 ros::serialization::serialize(stream, intensities);
00171 return stream.getData();
00172 }
00173
00174 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)
00175 {
00176 ros::serialization::IStream stream(read_ptr, 1000000000);
00177 ros::serialization::deserialize(stream, header);
00178 ros::serialization::deserialize(stream, angle_min);
00179 ros::serialization::deserialize(stream, angle_max);
00180 ros::serialization::deserialize(stream, angle_increment);
00181 ros::serialization::deserialize(stream, time_increment);
00182 ros::serialization::deserialize(stream, scan_time);
00183 ros::serialization::deserialize(stream, range_min);
00184 ros::serialization::deserialize(stream, range_max);
00185 ros::serialization::deserialize(stream, ranges);
00186 ros::serialization::deserialize(stream, intensities);
00187 return stream.getData();
00188 }
00189
00190 ROS_DEPRECATED virtual uint32_t serializationLength() const
00191 {
00192 uint32_t size = 0;
00193 size += ros::serialization::serializationLength(header);
00194 size += ros::serialization::serializationLength(angle_min);
00195 size += ros::serialization::serializationLength(angle_max);
00196 size += ros::serialization::serializationLength(angle_increment);
00197 size += ros::serialization::serializationLength(time_increment);
00198 size += ros::serialization::serializationLength(scan_time);
00199 size += ros::serialization::serializationLength(range_min);
00200 size += ros::serialization::serializationLength(range_max);
00201 size += ros::serialization::serializationLength(ranges);
00202 size += ros::serialization::serializationLength(intensities);
00203 return size;
00204 }
00205
00206 typedef boost::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> > Ptr;
00207 typedef boost::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> const> ConstPtr;
00208 };
00209 typedef ::sensor_msgs::LaserScan_<std::allocator<void> > LaserScan;
00210
00211 typedef boost::shared_ptr< ::sensor_msgs::LaserScan> LaserScanPtr;
00212 typedef boost::shared_ptr< ::sensor_msgs::LaserScan const> LaserScanConstPtr;
00213
00214
00215 template<typename ContainerAllocator>
00216 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::LaserScan_<ContainerAllocator> & v)
00217 {
00218 ros::message_operations::Printer< ::sensor_msgs::LaserScan_<ContainerAllocator> >::stream(s, "", v);
00219 return s;}
00220
00221 }
00222
00223 namespace ros
00224 {
00225 namespace message_traits
00226 {
00227 template<class ContainerAllocator>
00228 struct MD5Sum< ::sensor_msgs::LaserScan_<ContainerAllocator> > {
00229 static const char* value()
00230 {
00231 return "90c7ef2dc6895d81024acba2ac42f369";
00232 }
00233
00234 static const char* value(const ::sensor_msgs::LaserScan_<ContainerAllocator> &) { return value(); }
00235 static const uint64_t static_value1 = 0x90c7ef2dc6895d81ULL;
00236 static const uint64_t static_value2 = 0x024acba2ac42f369ULL;
00237 };
00238
00239 template<class ContainerAllocator>
00240 struct DataType< ::sensor_msgs::LaserScan_<ContainerAllocator> > {
00241 static const char* value()
00242 {
00243 return "sensor_msgs/LaserScan";
00244 }
00245
00246 static const char* value(const ::sensor_msgs::LaserScan_<ContainerAllocator> &) { return value(); }
00247 };
00248
00249 template<class ContainerAllocator>
00250 struct Definition< ::sensor_msgs::LaserScan_<ContainerAllocator> > {
00251 static const char* value()
00252 {
00253 return "# Single scan from a planar laser range-finder\n\
00254 #\n\
00255 # If you have another ranging device with different behavior (e.g. a sonar\n\
00256 # array), please find or create a different message, since applications\n\
00257 # will make fairly laser-specific assumptions about this data\n\
00258 \n\
00259 Header header # timestamp in the header is the acquisition time of \n\
00260 # the first ray in the scan.\n\
00261 #\n\
00262 # in frame frame_id, angles are measured around \n\
00263 # the positive Z axis (counterclockwise, if Z is up)\n\
00264 # with zero angle being forward along the x axis\n\
00265 \n\
00266 float32 angle_min # start angle of the scan [rad]\n\
00267 float32 angle_max # end angle of the scan [rad]\n\
00268 float32 angle_increment # angular distance between measurements [rad]\n\
00269 \n\
00270 float32 time_increment # time between measurements [seconds] - if your scanner\n\
00271 # is moving, this will be used in interpolating position\n\
00272 # of 3d points\n\
00273 float32 scan_time # time between scans [seconds]\n\
00274 \n\
00275 float32 range_min # minimum range value [m]\n\
00276 float32 range_max # maximum range value [m]\n\
00277 \n\
00278 float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)\n\
00279 float32[] intensities # intensity data [device-specific units]. If your\n\
00280 # device does not provide intensities, please leave\n\
00281 # the array empty.\n\
00282 \n\
00283 ================================================================================\n\
00284 MSG: std_msgs/Header\n\
00285 # Standard metadata for higher-level stamped data types.\n\
00286 # This is generally used to communicate timestamped data \n\
00287 # in a particular coordinate frame.\n\
00288 # \n\
00289 # sequence ID: consecutively increasing ID \n\
00290 uint32 seq\n\
00291 #Two-integer timestamp that is expressed as:\n\
00292 # * stamp.secs: seconds (stamp_secs) since epoch\n\
00293 # * stamp.nsecs: nanoseconds since stamp_secs\n\
00294 # time-handling sugar is provided by the client library\n\
00295 time stamp\n\
00296 #Frame this data is associated with\n\
00297 # 0: no frame\n\
00298 # 1: global frame\n\
00299 string frame_id\n\
00300 \n\
00301 ";
00302 }
00303
00304 static const char* value(const ::sensor_msgs::LaserScan_<ContainerAllocator> &) { return value(); }
00305 };
00306
00307 template<class ContainerAllocator> struct HasHeader< ::sensor_msgs::LaserScan_<ContainerAllocator> > : public TrueType {};
00308 template<class ContainerAllocator> struct HasHeader< const ::sensor_msgs::LaserScan_<ContainerAllocator> > : public TrueType {};
00309 }
00310 }
00311
00312 namespace ros
00313 {
00314 namespace serialization
00315 {
00316
00317 template<class ContainerAllocator> struct Serializer< ::sensor_msgs::LaserScan_<ContainerAllocator> >
00318 {
00319 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
00320 {
00321 stream.next(m.header);
00322 stream.next(m.angle_min);
00323 stream.next(m.angle_max);
00324 stream.next(m.angle_increment);
00325 stream.next(m.time_increment);
00326 stream.next(m.scan_time);
00327 stream.next(m.range_min);
00328 stream.next(m.range_max);
00329 stream.next(m.ranges);
00330 stream.next(m.intensities);
00331 }
00332
00333 ROS_DECLARE_ALLINONE_SERIALIZER;
00334 };
00335 }
00336 }
00337
00338 namespace ros
00339 {
00340 namespace message_operations
00341 {
00342
00343 template<class ContainerAllocator>
00344 struct Printer< ::sensor_msgs::LaserScan_<ContainerAllocator> >
00345 {
00346 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::LaserScan_<ContainerAllocator> & v)
00347 {
00348 s << indent << "header: ";
00349 s << std::endl;
00350 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header);
00351 s << indent << "angle_min: ";
00352 Printer<float>::stream(s, indent + " ", v.angle_min);
00353 s << indent << "angle_max: ";
00354 Printer<float>::stream(s, indent + " ", v.angle_max);
00355 s << indent << "angle_increment: ";
00356 Printer<float>::stream(s, indent + " ", v.angle_increment);
00357 s << indent << "time_increment: ";
00358 Printer<float>::stream(s, indent + " ", v.time_increment);
00359 s << indent << "scan_time: ";
00360 Printer<float>::stream(s, indent + " ", v.scan_time);
00361 s << indent << "range_min: ";
00362 Printer<float>::stream(s, indent + " ", v.range_min);
00363 s << indent << "range_max: ";
00364 Printer<float>::stream(s, indent + " ", v.range_max);
00365 s << indent << "ranges[]" << std::endl;
00366 for (size_t i = 0; i < v.ranges.size(); ++i)
00367 {
00368 s << indent << " ranges[" << i << "]: ";
00369 Printer<float>::stream(s, indent + " ", v.ranges[i]);
00370 }
00371 s << indent << "intensities[]" << std::endl;
00372 for (size_t i = 0; i < v.intensities.size(); ++i)
00373 {
00374 s << indent << " intensities[" << i << "]: ";
00375 Printer<float>::stream(s, indent + " ", v.intensities[i]);
00376 }
00377 }
00378 };
00379
00380
00381 }
00382 }
00383
00384 #endif // SENSOR_MSGS_MESSAGE_LASERSCAN_H
00385