This class is used to obtain pcl::PointCloud from CAD file. Supported formats: .OBJ. More...
#include <CADToPointCloud.h>
Public Member Functions | |
| CADToPointCloud (const std::string &cad_file_path, int sample_points) | |
| Construct a new CADToPointCloud object. More... | |
| void | convertCloud (PointCloudRGB::Ptr cloud) |
| convert cloud defined by path in construstor into cloud More... | |
| ~CADToPointCloud () | |
| Destroy the CADToPointCloud object. More... | |
Private Types | |
| typedef pcl::PointCloud< pcl::PointXYZRGB > | PointCloudRGB |
| typedef pcl::PointCloud< pcl::PointXYZ > | PointCloudXYZ |
Private Member Functions | |
| 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, Willow Garage, Inc. More... | |
| 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, Willow Garage, Inc. More... | |
| double | uniformDeviate (int seed) |
| Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp Copyright (c) 2010-2011, Willow Garage, Inc. More... | |
| 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, Willow Garage, Inc. More... | |
Private Attributes | |
| std::string | cad_file_path_ |
| path to CAD file to be converted. More... | |
| std::string | extension_ |
| cad file path extension to check formats. More... | |
| int | SAMPLE_POINTS_ |
| number of points to sample CAD mesh. More... | |
This class is used to obtain pcl::PointCloud from CAD file. Supported formats: .OBJ.
Definition at line 32 of file CADToPointCloud.h.
|
private |
Definition at line 35 of file CADToPointCloud.h.
|
private |
Definition at line 34 of file CADToPointCloud.h.
| CADToPointCloud::CADToPointCloud | ( | const std::string & | cad_file_path, |
| int | sample_points | ||
| ) |
Construct a new CADToPointCloud object.
| [in] | cad_file_path | Supported formats: .OBJ .PLY |
Definition at line 24 of file CADToPointCloud.cpp.
|
inline |
Destroy the CADToPointCloud object.
Definition at line 49 of file CADToPointCloud.h.
| void CADToPointCloud::convertCloud | ( | PointCloudRGB::Ptr | cloud | ) |
convert cloud defined by path in construstor into cloud
| [out] | cloud | to store cad converted to cloud |
Definition at line 35 of file CADToPointCloud.cpp.
|
private |
Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp
Copyright (c) 2010-2011, Willow Garage, Inc.
Definition at line 169 of file CADToPointCloud.cpp.
|
private |
Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp
Copyright (c) 2010-2011, Willow Garage, Inc.
Definition at line 144 of file CADToPointCloud.cpp.
|
private |
Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp
Copyright (c) 2010-2011, Willow Garage, Inc.
Definition at line 163 of file CADToPointCloud.cpp.
|
private |
Extracted from Point Cloud Library (PCL) –> pcl/tools/mesh_sampling.cpp
Copyright (c) 2010-2011, Willow Garage, Inc.
Definition at line 101 of file CADToPointCloud.cpp.
|
private |
path to CAD file to be converted.
Definition at line 64 of file CADToPointCloud.h.
|
private |
cad file path extension to check formats.
Definition at line 61 of file CADToPointCloud.h.
|
private |
number of points to sample CAD mesh.
Definition at line 67 of file CADToPointCloud.h.