$search
00001 /* Auto-generated by genmsg_cpp for file /home/rosbuild/hudson/workspace/doc-electric-perception_pcl/doc_stacks/2013-03-01_16-23-48.157924/perception_pcl/pcl/msg/PolygonMesh.msg */ 00002 #ifndef PCL_MESSAGE_POLYGONMESH_H 00003 #define PCL_MESSAGE_POLYGONMESH_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 #include "sensor_msgs/PointCloud2.h" 00019 #include "pcl/Vertices.h" 00020 00021 namespace pcl 00022 { 00023 template <class ContainerAllocator> 00024 struct PolygonMesh_ { 00025 typedef PolygonMesh_<ContainerAllocator> Type; 00026 00027 PolygonMesh_() 00028 : header() 00029 , cloud() 00030 , polygons() 00031 { 00032 } 00033 00034 PolygonMesh_(const ContainerAllocator& _alloc) 00035 : header(_alloc) 00036 , cloud(_alloc) 00037 , polygons(_alloc) 00038 { 00039 } 00040 00041 typedef ::std_msgs::Header_<ContainerAllocator> _header_type; 00042 ::std_msgs::Header_<ContainerAllocator> header; 00043 00044 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _cloud_type; 00045 ::sensor_msgs::PointCloud2_<ContainerAllocator> cloud; 00046 00047 typedef std::vector< ::pcl::Vertices_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pcl::Vertices_<ContainerAllocator> >::other > _polygons_type; 00048 std::vector< ::pcl::Vertices_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pcl::Vertices_<ContainerAllocator> >::other > polygons; 00049 00050 00051 ROS_DEPRECATED uint32_t get_polygons_size() const { return (uint32_t)polygons.size(); } 00052 ROS_DEPRECATED void set_polygons_size(uint32_t size) { polygons.resize((size_t)size); } 00053 ROS_DEPRECATED void get_polygons_vec(std::vector< ::pcl::Vertices_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pcl::Vertices_<ContainerAllocator> >::other > & vec) const { vec = this->polygons; } 00054 ROS_DEPRECATED void set_polygons_vec(const std::vector< ::pcl::Vertices_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pcl::Vertices_<ContainerAllocator> >::other > & vec) { this->polygons = vec; } 00055 private: 00056 static const char* __s_getDataType_() { return "pcl/PolygonMesh"; } 00057 public: 00058 ROS_DEPRECATED static const std::string __s_getDataType() { return __s_getDataType_(); } 00059 00060 ROS_DEPRECATED const std::string __getDataType() const { return __s_getDataType_(); } 00061 00062 private: 00063 static const char* __s_getMD5Sum_() { return "45a5fc6ad2cde8489600a790acc9a38a"; } 00064 public: 00065 ROS_DEPRECATED static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } 00066 00067 ROS_DEPRECATED const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } 00068 00069 private: 00070 static const char* __s_getMessageDefinition_() { return "# Separate header for the polygonal surface\n\ 00071 Header header\n\ 00072 # Vertices of the mesh as a point cloud\n\ 00073 sensor_msgs/PointCloud2 cloud\n\ 00074 # List of polygons\n\ 00075 Vertices[] polygons\n\ 00076 \n\ 00077 ================================================================================\n\ 00078 MSG: std_msgs/Header\n\ 00079 # Standard metadata for higher-level stamped data types.\n\ 00080 # This is generally used to communicate timestamped data \n\ 00081 # in a particular coordinate frame.\n\ 00082 # \n\ 00083 # sequence ID: consecutively increasing ID \n\ 00084 uint32 seq\n\ 00085 #Two-integer timestamp that is expressed as:\n\ 00086 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00087 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00088 # time-handling sugar is provided by the client library\n\ 00089 time stamp\n\ 00090 #Frame this data is associated with\n\ 00091 # 0: no frame\n\ 00092 # 1: global frame\n\ 00093 string frame_id\n\ 00094 \n\ 00095 ================================================================================\n\ 00096 MSG: sensor_msgs/PointCloud2\n\ 00097 # This message holds a collection of N-dimensional points, which may\n\ 00098 # contain additional information such as normals, intensity, etc. The\n\ 00099 # point data is stored as a binary blob, its layout described by the\n\ 00100 # contents of the \"fields\" array.\n\ 00101 \n\ 00102 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00103 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00104 # camera depth sensors such as stereo or time-of-flight.\n\ 00105 \n\ 00106 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00107 # points).\n\ 00108 Header header\n\ 00109 \n\ 00110 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00111 # 1 and width is the length of the point cloud.\n\ 00112 uint32 height\n\ 00113 uint32 width\n\ 00114 \n\ 00115 # Describes the channels and their layout in the binary data blob.\n\ 00116 PointField[] fields\n\ 00117 \n\ 00118 bool is_bigendian # Is this data bigendian?\n\ 00119 uint32 point_step # Length of a point in bytes\n\ 00120 uint32 row_step # Length of a row in bytes\n\ 00121 uint8[] data # Actual point data, size is (row_step*height)\n\ 00122 \n\ 00123 bool is_dense # True if there are no invalid points\n\ 00124 \n\ 00125 ================================================================================\n\ 00126 MSG: sensor_msgs/PointField\n\ 00127 # This message holds the description of one point entry in the\n\ 00128 # PointCloud2 message format.\n\ 00129 uint8 INT8 = 1\n\ 00130 uint8 UINT8 = 2\n\ 00131 uint8 INT16 = 3\n\ 00132 uint8 UINT16 = 4\n\ 00133 uint8 INT32 = 5\n\ 00134 uint8 UINT32 = 6\n\ 00135 uint8 FLOAT32 = 7\n\ 00136 uint8 FLOAT64 = 8\n\ 00137 \n\ 00138 string name # Name of field\n\ 00139 uint32 offset # Offset from start of point struct\n\ 00140 uint8 datatype # Datatype enumeration, see above\n\ 00141 uint32 count # How many elements in the field\n\ 00142 \n\ 00143 ================================================================================\n\ 00144 MSG: pcl/Vertices\n\ 00145 # List of point indices\n\ 00146 uint32[] vertices\n\ 00147 \n\ 00148 "; } 00149 public: 00150 ROS_DEPRECATED static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } 00151 00152 ROS_DEPRECATED const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } 00153 00154 ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const 00155 { 00156 ros::serialization::OStream stream(write_ptr, 1000000000); 00157 ros::serialization::serialize(stream, header); 00158 ros::serialization::serialize(stream, cloud); 00159 ros::serialization::serialize(stream, polygons); 00160 return stream.getData(); 00161 } 00162 00163 ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr) 00164 { 00165 ros::serialization::IStream stream(read_ptr, 1000000000); 00166 ros::serialization::deserialize(stream, header); 00167 ros::serialization::deserialize(stream, cloud); 00168 ros::serialization::deserialize(stream, polygons); 00169 return stream.getData(); 00170 } 00171 00172 ROS_DEPRECATED virtual uint32_t serializationLength() const 00173 { 00174 uint32_t size = 0; 00175 size += ros::serialization::serializationLength(header); 00176 size += ros::serialization::serializationLength(cloud); 00177 size += ros::serialization::serializationLength(polygons); 00178 return size; 00179 } 00180 00181 typedef boost::shared_ptr< ::pcl::PolygonMesh_<ContainerAllocator> > Ptr; 00182 typedef boost::shared_ptr< ::pcl::PolygonMesh_<ContainerAllocator> const> ConstPtr; 00183 boost::shared_ptr<std::map<std::string, std::string> > __connection_header; 00184 }; // struct PolygonMesh 00185 typedef ::pcl::PolygonMesh_<std::allocator<void> > PolygonMesh; 00186 00187 typedef boost::shared_ptr< ::pcl::PolygonMesh> PolygonMeshPtr; 00188 typedef boost::shared_ptr< ::pcl::PolygonMesh const> PolygonMeshConstPtr; 00189 00190 00191 template<typename ContainerAllocator> 00192 std::ostream& operator<<(std::ostream& s, const ::pcl::PolygonMesh_<ContainerAllocator> & v) 00193 { 00194 ros::message_operations::Printer< ::pcl::PolygonMesh_<ContainerAllocator> >::stream(s, "", v); 00195 return s;} 00196 00197 } // namespace pcl 00198 00199 namespace ros 00200 { 00201 namespace message_traits 00202 { 00203 template<class ContainerAllocator> struct IsMessage< ::pcl::PolygonMesh_<ContainerAllocator> > : public TrueType {}; 00204 template<class ContainerAllocator> struct IsMessage< ::pcl::PolygonMesh_<ContainerAllocator> const> : public TrueType {}; 00205 template<class ContainerAllocator> 00206 struct MD5Sum< ::pcl::PolygonMesh_<ContainerAllocator> > { 00207 static const char* value() 00208 { 00209 return "45a5fc6ad2cde8489600a790acc9a38a"; 00210 } 00211 00212 static const char* value(const ::pcl::PolygonMesh_<ContainerAllocator> &) { return value(); } 00213 static const uint64_t static_value1 = 0x45a5fc6ad2cde848ULL; 00214 static const uint64_t static_value2 = 0x9600a790acc9a38aULL; 00215 }; 00216 00217 template<class ContainerAllocator> 00218 struct DataType< ::pcl::PolygonMesh_<ContainerAllocator> > { 00219 static const char* value() 00220 { 00221 return "pcl/PolygonMesh"; 00222 } 00223 00224 static const char* value(const ::pcl::PolygonMesh_<ContainerAllocator> &) { return value(); } 00225 }; 00226 00227 template<class ContainerAllocator> 00228 struct Definition< ::pcl::PolygonMesh_<ContainerAllocator> > { 00229 static const char* value() 00230 { 00231 return "# Separate header for the polygonal surface\n\ 00232 Header header\n\ 00233 # Vertices of the mesh as a point cloud\n\ 00234 sensor_msgs/PointCloud2 cloud\n\ 00235 # List of polygons\n\ 00236 Vertices[] polygons\n\ 00237 \n\ 00238 ================================================================================\n\ 00239 MSG: std_msgs/Header\n\ 00240 # Standard metadata for higher-level stamped data types.\n\ 00241 # This is generally used to communicate timestamped data \n\ 00242 # in a particular coordinate frame.\n\ 00243 # \n\ 00244 # sequence ID: consecutively increasing ID \n\ 00245 uint32 seq\n\ 00246 #Two-integer timestamp that is expressed as:\n\ 00247 # * stamp.secs: seconds (stamp_secs) since epoch\n\ 00248 # * stamp.nsecs: nanoseconds since stamp_secs\n\ 00249 # time-handling sugar is provided by the client library\n\ 00250 time stamp\n\ 00251 #Frame this data is associated with\n\ 00252 # 0: no frame\n\ 00253 # 1: global frame\n\ 00254 string frame_id\n\ 00255 \n\ 00256 ================================================================================\n\ 00257 MSG: sensor_msgs/PointCloud2\n\ 00258 # This message holds a collection of N-dimensional points, which may\n\ 00259 # contain additional information such as normals, intensity, etc. The\n\ 00260 # point data is stored as a binary blob, its layout described by the\n\ 00261 # contents of the \"fields\" array.\n\ 00262 \n\ 00263 # The point cloud data may be organized 2d (image-like) or 1d\n\ 00264 # (unordered). Point clouds organized as 2d images may be produced by\n\ 00265 # camera depth sensors such as stereo or time-of-flight.\n\ 00266 \n\ 00267 # Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ 00268 # points).\n\ 00269 Header header\n\ 00270 \n\ 00271 # 2D structure of the point cloud. If the cloud is unordered, height is\n\ 00272 # 1 and width is the length of the point cloud.\n\ 00273 uint32 height\n\ 00274 uint32 width\n\ 00275 \n\ 00276 # Describes the channels and their layout in the binary data blob.\n\ 00277 PointField[] fields\n\ 00278 \n\ 00279 bool is_bigendian # Is this data bigendian?\n\ 00280 uint32 point_step # Length of a point in bytes\n\ 00281 uint32 row_step # Length of a row in bytes\n\ 00282 uint8[] data # Actual point data, size is (row_step*height)\n\ 00283 \n\ 00284 bool is_dense # True if there are no invalid points\n\ 00285 \n\ 00286 ================================================================================\n\ 00287 MSG: sensor_msgs/PointField\n\ 00288 # This message holds the description of one point entry in the\n\ 00289 # PointCloud2 message format.\n\ 00290 uint8 INT8 = 1\n\ 00291 uint8 UINT8 = 2\n\ 00292 uint8 INT16 = 3\n\ 00293 uint8 UINT16 = 4\n\ 00294 uint8 INT32 = 5\n\ 00295 uint8 UINT32 = 6\n\ 00296 uint8 FLOAT32 = 7\n\ 00297 uint8 FLOAT64 = 8\n\ 00298 \n\ 00299 string name # Name of field\n\ 00300 uint32 offset # Offset from start of point struct\n\ 00301 uint8 datatype # Datatype enumeration, see above\n\ 00302 uint32 count # How many elements in the field\n\ 00303 \n\ 00304 ================================================================================\n\ 00305 MSG: pcl/Vertices\n\ 00306 # List of point indices\n\ 00307 uint32[] vertices\n\ 00308 \n\ 00309 "; 00310 } 00311 00312 static const char* value(const ::pcl::PolygonMesh_<ContainerAllocator> &) { return value(); } 00313 }; 00314 00315 template<class ContainerAllocator> struct HasHeader< ::pcl::PolygonMesh_<ContainerAllocator> > : public TrueType {}; 00316 template<class ContainerAllocator> struct HasHeader< const ::pcl::PolygonMesh_<ContainerAllocator> > : public TrueType {}; 00317 } // namespace message_traits 00318 } // namespace ros 00319 00320 namespace ros 00321 { 00322 namespace serialization 00323 { 00324 00325 template<class ContainerAllocator> struct Serializer< ::pcl::PolygonMesh_<ContainerAllocator> > 00326 { 00327 template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m) 00328 { 00329 stream.next(m.header); 00330 stream.next(m.cloud); 00331 stream.next(m.polygons); 00332 } 00333 00334 ROS_DECLARE_ALLINONE_SERIALIZER; 00335 }; // struct PolygonMesh_ 00336 } // namespace serialization 00337 } // namespace ros 00338 00339 namespace ros 00340 { 00341 namespace message_operations 00342 { 00343 00344 template<class ContainerAllocator> 00345 struct Printer< ::pcl::PolygonMesh_<ContainerAllocator> > 00346 { 00347 template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::pcl::PolygonMesh_<ContainerAllocator> & v) 00348 { 00349 s << indent << "header: "; 00350 s << std::endl; 00351 Printer< ::std_msgs::Header_<ContainerAllocator> >::stream(s, indent + " ", v.header); 00352 s << indent << "cloud: "; 00353 s << std::endl; 00354 Printer< ::sensor_msgs::PointCloud2_<ContainerAllocator> >::stream(s, indent + " ", v.cloud); 00355 s << indent << "polygons[]" << std::endl; 00356 for (size_t i = 0; i < v.polygons.size(); ++i) 00357 { 00358 s << indent << " polygons[" << i << "]: "; 00359 s << std::endl; 00360 s << indent; 00361 Printer< ::pcl::Vertices_<ContainerAllocator> >::stream(s, indent + " ", v.polygons[i]); 00362 } 00363 } 00364 }; 00365 00366 00367 } // namespace message_operations 00368 } // namespace ros 00369 00370 #endif // PCL_MESSAGE_POLYGONMESH_H 00371