#include <TextureMesh.h>
Public Types | |
typedef boost::shared_ptr < pcl::TextureMesh const > | ConstPtr |
typedef boost::shared_ptr < pcl::TextureMesh > | Ptr |
Public Member Functions | |
TextureMesh () | |
Public Attributes | |
sensor_msgs::PointCloud2 | cloud |
std_msgs::Header | header |
std::vector< std::vector < Eigen::Vector2f > > | tex_coordinates |
std::vector< pcl::TexMaterial > | tex_materials |
std::vector< std::vector < pcl::Vertices > > | tex_polygons |
Definition at line 94 of file TextureMesh.h.
typedef boost::shared_ptr<pcl::TextureMesh const> pcl::TextureMesh::ConstPtr |
Definition at line 108 of file TextureMesh.h.
typedef boost::shared_ptr<pcl::TextureMesh> pcl::TextureMesh::Ptr |
Definition at line 107 of file TextureMesh.h.
pcl::TextureMesh::TextureMesh | ( | ) | [inline] |
Definition at line 96 of file TextureMesh.h.
sensor_msgs::PointCloud2 pcl::TextureMesh::cloud |
Definition at line 100 of file TextureMesh.h.
Definition at line 99 of file TextureMesh.h.
std::vector<std::vector<Eigen::Vector2f> > pcl::TextureMesh::tex_coordinates |
Definition at line 103 of file TextureMesh.h.
std::vector<pcl::TexMaterial> pcl::TextureMesh::tex_materials |
Definition at line 104 of file TextureMesh.h.
std::vector<std::vector<pcl::Vertices> > pcl::TextureMesh::tex_polygons |
Definition at line 102 of file TextureMesh.h.