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