00001 /* Auto-generated by genmsg_cpp for file /work/ros/pkgs-trunk/point_cloud_perception/pcl/msg/PolygonMesh.msg */ 00002 #ifndef PCL_MESSAGE_POLYGONMESH_H 00003 #define PCL_MESSAGE_POLYGONMESH_H 00004 #include <string> 00005 #include <vector> 00006 #include <ostream> 00007 00008 // Include the correct Header path here 00009 #include "Header.h" 00010 #include "PointCloud2.h" 00011 #include "Vertices.h" 00012 00013 namespace pcl 00014 { 00015 template <class ContainerAllocator> 00016 struct PolygonMesh_ 00017 { 00018 typedef PolygonMesh_<ContainerAllocator> Type; 00019 00020 PolygonMesh_() 00021 : header() 00022 , cloud() 00023 , polygons() 00024 { 00025 } 00026 00027 PolygonMesh_(const ContainerAllocator& _alloc) 00028 : header(_alloc) 00029 , cloud(_alloc) 00030 , polygons(_alloc) 00031 { 00032 } 00033 00034 typedef ::roslib::Header_<ContainerAllocator> _header_type; 00035 ::roslib::Header_<ContainerAllocator> header; 00036 00037 typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _cloud_type; 00038 ::sensor_msgs::PointCloud2_<ContainerAllocator> cloud; 00039 00040 typedef std::vector< ::pcl::Vertices_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pcl::Vertices_<ContainerAllocator> >::other > _polygons_type; 00041 std::vector< ::pcl::Vertices_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::pcl::Vertices_<ContainerAllocator> >::other > polygons; 00042 00043 00044 public: 00045 typedef boost::shared_ptr< ::pcl::PolygonMesh_<ContainerAllocator> > Ptr; 00046 typedef boost::shared_ptr< ::pcl::PolygonMesh_<ContainerAllocator> const> ConstPtr; 00047 }; // struct PolygonMesh 00048 typedef ::pcl::PolygonMesh_<std::allocator<void> > PolygonMesh; 00049 00050 typedef boost::shared_ptr< ::pcl::PolygonMesh> PolygonMeshPtr; 00051 typedef boost::shared_ptr< ::pcl::PolygonMesh const> PolygonMeshConstPtr; 00052 00053 } // namespace pcl 00054 00055 #endif // PCL_MESSAGE_POLYGONMESH_H 00056