$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-pr2_calibration/doc_stacks/2013-03-01_16-35-11.769043/pr2_calibration/calibration_msgs/msg/DenseLaserSnapshot.msg */ 00002 #ifndef CALIBRATION_MSGS_MESSAGE_DENSELASERSNAPSHOT_H 00003 #define CALIBRATION_MSGS_MESSAGE_DENSELASERSNAPSHOT_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 calibration_msgs 00020 { 00021 template <class ContainerAllocator> 00022 struct DenseLaserSnapshot_ { 00023 typedef DenseLaserSnapshot_<ContainerAllocator> Type; 00024 00025 DenseLaserSnapshot_() 00026 : header() 00027 , angle_min(0.0) 00028 , angle_max(0.0) 00029 , angle_increment(0.0) 00030 , time_increment(0.0) 00031 , range_min(0.0) 00032 , range_max(0.0) 00033 , readings_per_scan(0) 00034 , num_scans(0) 00035 , ranges() 00036 , intensities() 00037 , scan_start() 00038 { 00039 } 00040 00041 DenseLaserSnapshot_(const ContainerAllocator& _alloc) 00042 : header(_alloc) 00043 , angle_min(0.0) 00044 , angle_max(0.0) 00045 , angle_increment(0.0) 00046 , time_increment(0.0) 00047 , range_min(0.0) 00048 , range_max(0.0) 00049 , readings_per_scan(0) 00050 , num_scans(0) 00051 , ranges(_alloc) 00052 , intensities(_alloc) 00053 , scan_start(_alloc) 00054 { 00055 } 00056 00057 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00058 ::std_msgs::Header_<ContainerAllocator> header; 00059 00060 typedef float _angle_min_type; 00061 float angle_min; 00062 00063 typedef float _angle_max_type; 00064 float angle_max; 00065 00066 typedef float _angle_increment_type; 00067 float angle_increment; 00068 00069 typedef float _time_increment_type; 00070 float time_increment; 00071 00072 typedef float _range_min_type; 00073 float range_min; 00074 00075 typedef float _range_max_type; 00076 float range_max; 00077 00078 typedef uint32_t _readings_per_scan_type; 00079 uint32_t readings_per_scan; 00080 00081 typedef uint32_t _num_scans_type; 00082 uint32_t num_scans; 00083 00084 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _ranges_type; 00085 std::vector<float, typename ContainerAllocator::template rebind<float>::other > ranges; 00086 00087 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _intensities_type; 00088 std::vector<float, typename ContainerAllocator::template rebind<float>::other > intensities; 00089 00090 typedef std::vector<ros::Time, typename ContainerAllocator::template rebind<ros::Time>::other > _scan_start_type; 00091 std::vector<ros::Time, typename ContainerAllocator::template rebind<ros::Time>::other > scan_start; 00092 00093 00094 ROS_DEPRECATED uint32_t get_ranges_size() const { return (uint32_t)ranges.size(); } 00095 ROS_DEPRECATED void set_ranges_size(uint32_t size) { ranges.resize((size_t)size); } 00096 ROS_DEPRECATED void get_ranges_vec(std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) const { vec = this->ranges; } 00097 ROS_DEPRECATED void set_ranges_vec(const std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) { this->ranges = vec; } 00098 ROS_DEPRECATED uint32_t get_intensities_size() const { return (uint32_t)intensities.size(); } 00099 ROS_DEPRECATED void set_intensities_size(uint32_t size) { intensities.resize((size_t)size); } 00100 ROS_DEPRECATED void get_intensities_vec(std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) const { vec = this->intensities; } 00101 ROS_DEPRECATED void set_intensities_vec(const std::vector<float, typename ContainerAllocator::template rebind<float>::other > & vec) { this->intensities = vec; } 00102 ROS_DEPRECATED uint32_t get_scan_start_size() const { return (uint32_t)scan_start.size(); } 00103 ROS_DEPRECATED void set_scan_start_size(uint32_t size) { scan_start.resize((size_t)size); } 00104 ROS_DEPRECATED void get_scan_start_vec(std::vector<ros::Time, typename ContainerAllocator::template rebind<ros::Time>::other > & vec) const { vec = this->scan_start; } 00105 ROS_DEPRECATED void set_scan_start_vec(const std::vector<ros::Time, typename ContainerAllocator::template rebind<ros::Time>::other > & vec) { this->scan_start = vec; } 00106 private: 00107 static const char* __s_getDataType_() { return "calibration_msgs/DenseLaserSnapshot"; } 00108 public: 00109 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00110 00111 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00112 00113 private: 00114 static const char* __s_getMD5Sum_() { return "deb2810d3530db3484f886a81243195d"; } 00115 public: 00116 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00117 00118 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00119 00120 private: 00121 static const char* __s_getMessageDefinition_() { return "# Provides all the state & sensor information for\n\ 00122 # a single sweep of laser attached to some mechanism.\n\ 00123 # Most likely, this will be used with PR2's tilting laser mechanism\n\ 00124 Header header\n\ 00125 \n\ 00126 # Store the laser intrinsics. This is very similar to the\n\ 00127 # intrinsics commonly stored in \n\ 00128 float32 angle_min # start angle of the scan [rad]\n\ 00129 float32 angle_max # end angle of the scan [rad]\n\ 00130 float32 angle_increment # angular distance between measurements [rad]\n\ 00131 float32 time_increment # time between measurements [seconds]\n\ 00132 float32 range_min # minimum range value [m]\n\ 00133 float32 range_max # maximum range value [m]\n\ 00134 \n\ 00135 # Define the size of the binary data\n\ 00136 uint32 readings_per_scan # (Width)\n\ 00137 uint32 num_scans # (Height)\n\ 00138 \n\ 00139 # 2D Arrays storing laser data.\n\ 00140 # We can think of each type data as being a single channel image.\n\ 00141 # Each row of the image has data from a single scan, and scans are\n\ 00142 # concatenated to form the entire 'image'.\n\ 00143 float32[] ranges # (Image data)\n\ 00144 float32[] intensities # (Image data)\n\ 00145 \n\ 00146 # Store the start time of each scan\n\ 00147 time[] scan_start\n\ 00148 \n\ 00149 ================================================================================\n\ 00150 MSG: std_msgs/Header\n\ 00151 # Standard metadata for higher-level stamped data types.\n\ 00152 # This is generally used to communicate timestamped data \n\ 00153 # in a particular coordinate frame.\n\ 00154 # \n\ 00155 # sequence ID: consecutively increasing ID \n\ 00156 uint32 seq\n\ 00157 #Two-integer timestamp that is expressed as:\n\ 00158 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00159 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00160 # time-handling sugar is provided by the client library\n\ 00161 time stamp\n\ 00162 #Frame this data is associated with\n\ 00163 # 0: no frame\n\ 00164 # 1: global frame\n\ 00165 string frame_id\n\ 00166 \n\ 00167 "; } 00168 public: 00169 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00170 00171 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00172 00173 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00174 { 00175 ros::serialization::OStream stream(write_ptr, 1000000000); 00176 ros::serialization::serialize(stream, header); 00177 ros::serialization::serialize(stream, angle_min); 00178 ros::serialization::serialize(stream, angle_max); 00179 ros::serialization::serialize(stream, angle_increment); 00180 ros::serialization::serialize(stream, time_increment); 00181 ros::serialization::serialize(stream, range_min); 00182 ros::serialization::serialize(stream, range_max); 00183 ros::serialization::serialize(stream, readings_per_scan); 00184 ros::serialization::serialize(stream, num_scans); 00185 ros::serialization::serialize(stream, ranges); 00186 ros::serialization::serialize(stream, intensities); 00187 ros::serialization::serialize(stream, scan_start); 00188 return stream.getData(); 00189 } 00190 00191 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00192 { 00193 ros::serialization::IStream stream(read_ptr, 1000000000); 00194 ros::serialization::deserialize(stream, header); 00195 ros::serialization::deserialize(stream, angle_min); 00196 ros::serialization::deserialize(stream, angle_max); 00197 ros::serialization::deserialize(stream, angle_increment); 00198 ros::serialization::deserialize(stream, time_increment); 00199 ros::serialization::deserialize(stream, range_min); 00200 ros::serialization::deserialize(stream, range_max); 00201 ros::serialization::deserialize(stream, readings_per_scan); 00202 ros::serialization::deserialize(stream, num_scans); 00203 ros::serialization::deserialize(stream, ranges); 00204 ros::serialization::deserialize(stream, intensities); 00205 ros::serialization::deserialize(stream, scan_start); 00206 return stream.getData(); 00207 } 00208 00209 ROS_DEPRECATED virtual uint32_t serializationLength() const 00210 { 00211 uint32_t size = 0; 00212 size += ros::serialization::serializationLength(header); 00213 size += ros::serialization::serializationLength(angle_min); 00214 size += ros::serialization::serializationLength(angle_max); 00215 size += ros::serialization::serializationLength(angle_increment); 00216 size += ros::serialization::serializationLength(time_increment); 00217 size += ros::serialization::serializationLength(range_min); 00218 size += ros::serialization::serializationLength(range_max); 00219 size += ros::serialization::serializationLength(readings_per_scan); 00220 size += ros::serialization::serializationLength(num_scans); 00221 size += ros::serialization::serializationLength(ranges); 00222 size += ros::serialization::serializationLength(intensities); 00223 size += ros::serialization::serializationLength(scan_start); 00224 return size; 00225 } 00226 00227 typedef boost::shared_ptr< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > Ptr; 00228 typedef boost::shared_ptr< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> const> ConstPtr; 00229 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00230 }; // struct DenseLaserSnapshot 00231 typedef ::calibration_msgs::DenseLaserSnapshot_<std::allocator<void> > DenseLaserSnapshot; 00232 00233 typedef boost::shared_ptr< ::calibration_msgs::DenseLaserSnapshot> DenseLaserSnapshotPtr; 00234 typedef boost::shared_ptr< ::calibration_msgs::DenseLaserSnapshot const> DenseLaserSnapshotConstPtr; 00235 00236 00237 template<typename ContainerAllocator> 00238 std::ostream& operator<<(std::ostream& s, const ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> & v) 00239 { 00240 ros::message_operations::Printer< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> >::stream(s, "", v); 00241 return s;} 00242 00243 } // namespace calibration_msgs 00244 00245 namespace ros 00246 { 00247 namespace message_traits 00248 { 00249 template<class ContainerAllocator> struct IsMessage< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > : public TrueType {}; 00250 template<class ContainerAllocator> struct IsMessage< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> const> : public TrueType {}; 00251 template<class ContainerAllocator> 00252 struct MD5Sum< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > { 00253 static const char* value() 00254 { 00255 return "deb2810d3530db3484f886a81243195d"; 00256 } 00257 00258 static const char* value(const ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> &) { return value(); } 00259 static const uint64_t static_value1 = 0xdeb2810d3530db34ULL; 00260 static const uint64_t static_value2 = 0x84f886a81243195dULL; 00261 }; 00262 00263 template<class ContainerAllocator> 00264 struct DataType< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > { 00265 static const char* value() 00266 { 00267 return "calibration_msgs/DenseLaserSnapshot"; 00268 } 00269 00270 static const char* value(const ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> &) { return value(); } 00271 }; 00272 00273 template<class ContainerAllocator> 00274 struct Definition< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > { 00275 static const char* value() 00276 { 00277 return "# Provides all the state & sensor information for\n\ 00278 # a single sweep of laser attached to some mechanism.\n\ 00279 # Most likely, this will be used with PR2's tilting laser mechanism\n\ 00280 Header header\n\ 00281 \n\ 00282 # Store the laser intrinsics. This is very similar to the\n\ 00283 # intrinsics commonly stored in \n\ 00284 float32 angle_min # start angle of the scan [rad]\n\ 00285 float32 angle_max # end angle of the scan [rad]\n\ 00286 float32 angle_increment # angular distance between measurements [rad]\n\ 00287 float32 time_increment # time between measurements [seconds]\n\ 00288 float32 range_min # minimum range value [m]\n\ 00289 float32 range_max # maximum range value [m]\n\ 00290 \n\ 00291 # Define the size of the binary data\n\ 00292 uint32 readings_per_scan # (Width)\n\ 00293 uint32 num_scans # (Height)\n\ 00294 \n\ 00295 # 2D Arrays storing laser data.\n\ 00296 # We can think of each type data as being a single channel image.\n\ 00297 # Each row of the image has data from a single scan, and scans are\n\ 00298 # concatenated to form the entire 'image'.\n\ 00299 float32[] ranges # (Image data)\n\ 00300 float32[] intensities # (Image data)\n\ 00301 \n\ 00302 # Store the start time of each scan\n\ 00303 time[] scan_start\n\ 00304 \n\ 00305 ================================================================================\n\ 00306 MSG: std_msgs/Header\n\ 00307 # Standard metadata for higher-level stamped data types.\n\ 00308 # This is generally used to communicate timestamped data \n\ 00309 # in a particular coordinate frame.\n\ 00310 # \n\ 00311 # sequence ID: consecutively increasing ID \n\ 00312 uint32 seq\n\ 00313 #Two-integer timestamp that is expressed as:\n\ 00314 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00315 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00316 # time-handling sugar is provided by the client library\n\ 00317 time stamp\n\ 00318 #Frame this data is associated with\n\ 00319 # 0: no frame\n\ 00320 # 1: global frame\n\ 00321 string frame_id\n\ 00322 \n\ 00323 "; 00324 } 00325 00326 static const char* value(const ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> &) { return value(); } 00327 }; 00328 00329 template<class ContainerAllocator> struct HasHeader< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > : public TrueType {}; 00330 template<class ContainerAllocator> struct HasHeader< const ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > : public TrueType {}; 00331 } // namespace message_traits 00332 } // namespace ros 00333 00334 namespace ros 00335 { 00336 namespace serialization 00337 { 00338 00339 template<class ContainerAllocator> struct Serializer< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > 00340 { 00341 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00342 { 00343 stream.next(m.header); 00344 stream.next(m.angle_min); 00345 stream.next(m.angle_max); 00346 stream.next(m.angle_increment); 00347 stream.next(m.time_increment); 00348 stream.next(m.range_min); 00349 stream.next(m.range_max); 00350 stream.next(m.readings_per_scan); 00351 stream.next(m.num_scans); 00352 stream.next(m.ranges); 00353 stream.next(m.intensities); 00354 stream.next(m.scan_start); 00355 } 00356 00357 ROS_DECLARE_ALLINONE_SERIALIZER; 00358 }; // struct DenseLaserSnapshot_ 00359 } // namespace serialization 00360 } // namespace ros 00361 00362 namespace ros 00363 { 00364 namespace message_operations 00365 { 00366 00367 template<class ContainerAllocator> 00368 struct Printer< ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> > 00369 { 00370 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::calibration_msgs::DenseLaserSnapshot_<ContainerAllocator> & v) 00371 { 00372 s << indent << "header: "; 00373 s << std::endl; 00374 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00375 s << indent << "angle_min: "; 00376 Printer<float>::stream(s, indent + " ", v.angle_min); 00377 s << indent << "angle_max: "; 00378 Printer<float>::stream(s, indent + " ", v.angle_max); 00379 s << indent << "angle_increment: "; 00380 Printer<float>::stream(s, indent + " ", v.angle_increment); 00381 s << indent << "time_increment: "; 00382 Printer<float>::stream(s, indent + " ", v.time_increment); 00383 s << indent << "range_min: "; 00384 Printer<float>::stream(s, indent + " ", v.range_min); 00385 s << indent << "range_max: "; 00386 Printer<float>::stream(s, indent + " ", v.range_max); 00387 s << indent << "readings_per_scan: "; 00388 Printer<uint32_t>::stream(s, indent + " ", v.readings_per_scan); 00389 s << indent << "num_scans: "; 00390 Printer<uint32_t>::stream(s, indent + " ", v.num_scans); 00391 s << indent << "ranges[]" << std::endl; 00392 for (size_t i = 0; i < v.ranges.size(); ++i) 00393 { 00394 s << indent << " ranges[" << i << "]: "; 00395 Printer<float>::stream(s, indent + " ", v.ranges[i]); 00396 } 00397 s << indent << "intensities[]" << std::endl; 00398 for (size_t i = 0; i < v.intensities.size(); ++i) 00399 { 00400 s << indent << " intensities[" << i << "]: "; 00401 Printer<float>::stream(s, indent + " ", v.intensities[i]); 00402 } 00403 s << indent << "scan_start[]" << std::endl; 00404 for (size_t i = 0; i < v.scan_start.size(); ++i) 00405 { 00406 s << indent << " scan_start[" << i << "]: "; 00407 Printer<ros::Time>::stream(s, indent + " ", v.scan_start[i]); 00408 } 00409 } 00410 }; 00411 00412 00413 } // namespace message_operations 00414 } // namespace ros 00415 00416 #endif // CALIBRATION_MSGS_MESSAGE_DENSELASERSNAPSHOT_H 00417