19 #ifndef _CAD_TO_POINTCLOUD_H 20 #define _CAD_TO_POINTCLOUD_H 24 #include <pcl/io/vtk_lib_io.h> 108 void uniformSampling(vtkSmartPointer<vtkPolyData> polydata,
size_t n_samples, PointCloudRGB& cloud_out);
112 void randPSurface(vtkPolyData* polydata, std::vector<double>* cumulativeAreas,
double totalArea, Eigen::Vector4f& p);
116 void randomPointTriangle(
float a1,
float a2,
float a3,
float b1,
float b2,
float b3,
float c1,
float c2,
float c3,
int SAMPLE_POINTS_
number of points to sample CAD mesh.
~CADToPointCloud()
Destroy the CADToPointCloud object.
std::string extension_
cad file path extension to check formats.
void randPSurface(vtkPolyData *polydata, std::vector< double > *cumulativeAreas, double totalArea, Eigen::Vector4f &p)
Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp Copyright (c) 2010-2011...
std::string cad_file_path_
path to CAD file to be converted.
This class is used to obtain pcl::PointCloud from CAD file. Supported formats: .OBJ.
void convertCloud(PointCloudRGB::Ptr cloud)
convert cloud defined by path in construstor into cloud
double uniformDeviate(int seed)
Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp Copyright (c) 2010-2011...
CADToPointCloud(const std::string &cad_file_path, int sample_points)
Construct a new CADToPointCloud object.
void uniformSampling(vtkSmartPointer< vtkPolyData > polydata, size_t n_samples, PointCloudRGB &cloud_out)
Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp Copyright (c) 2010-2011...
pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
void randomPointTriangle(float a1, float a2, float a3, float b1, float b2, float b3, float c1, float c2, float c3, Eigen::Vector4f &p)
Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp Copyright (c) 2010-2011...