15 #include <pcl/io/pcd_io.h>
18 #include <pcl/features/fpfh.h>
19 #include <pcl/features/fpfh_omp.h>
21 #include <pcl/features/impl/normal_3d_omp.hpp>
24 #include <pcl/impl/instantiate.hpp>
25 #include <pcl/kdtree/impl/kdtree_flann.hpp>
26 #include <pcl/search/impl/search.hpp>
29 #include <pcl/segmentation/region_growing.h>
30 #include <pcl/segmentation/region_growing_rgb.h>
31 #include <pcl/segmentation/sac_segmentation.h>
34 #include <pcl/recognition/impl/cg/geometric_consistency.hpp>
37 #include <pcl/surface/gp3.h>
38 #include <pcl/surface/grid_projection.h>
39 #include <pcl/surface/poisson.h>
47 std::vector<pcl::PointIndices> &clusters,
48 PointCloudRGB::Ptr cloud_segmented,
52 unsigned int neighbour_number,
53 float smoothness_theta,
58 pcl::search::KdTree<PointT>::Ptr kdtree(
new pcl::search::KdTree<PointT>);
59 kdtree->setInputCloud(cloud);
62 pcl::RegionGrowing<PointT, NormalT> regionGrowing;
64 regionGrowing.setMinClusterSize(min_cluster_size);
66 regionGrowing.setMaxClusterSize(max_cluster_size);
68 regionGrowing.setSearchMethod(kdtree);
71 regionGrowing.setNumberOfNeighbours(
74 regionGrowing.setInputCloud(cloud);
77 regionGrowing.setInputNormals(
normals);
80 regionGrowing.setSmoothnessThreshold(smoothness_theta);
81 regionGrowing.setCurvatureThreshold(curvature);
83 regionGrowing.extract(clusters);
85 QString(
"[Basic Region Growing] Number of clusters is equal to %1")
86 .arg(clusters.size()));
87 if (clusters.size() != 0) {
89 QString(
"[Basic Region Growing] First cluster has %1 points.")
90 .arg(clusters[0].indices.size()));
93 pcl::copyPointCloud(*regionGrowing.getColoredCloud(), *cloud_segmented);
99 std::vector<pcl::PointIndices> &clusters,
100 PointCloudRGB::Ptr cloud_segmented,
101 int min_cluster_size,
102 float neighbors_distance,
103 float point_color_diff,
104 float region_color_diff) {
107 pcl::search::KdTree<PointRGB>::Ptr kdtree(
108 new pcl::search::KdTree<PointRGB>);
109 kdtree->setInputCloud(cloud);
112 pcl::RegionGrowingRGB<PointRGB> regionGrowing;
113 regionGrowing.setInputCloud(cloud);
114 regionGrowing.setSearchMethod(kdtree);
117 regionGrowing.setMinClusterSize(min_cluster_size);
120 regionGrowing.setDistanceThreshold(neighbors_distance);
122 regionGrowing.setPointColorThreshold(point_color_diff);
125 regionGrowing.setRegionColorThreshold(region_color_diff);
127 regionGrowing.extract(clusters);
129 QString(
"[RGB Region Growing] Number of clusters is equal to %1")
130 .arg(clusters.size()));
131 if (clusters.size() != 0) {
133 QString(
"[RGB Region Growing] First cluster has %1 points.")
134 .arg(clusters[0].indices.size()));
137 pcl::copyPointCloud(*regionGrowing.getColoredCloud(), *cloud_segmented);
143 pcl::PointIndices::Ptr inliers,
144 pcl::ModelCoefficients::Ptr coefficients ,
145 const int &methodType ,
146 const int &modelType ,
147 float distanceThreshold ,
150 float minRadiusLimits ,
151 float maxRadiusLimits ,
152 float normalDisWeight ) {
155 case pcl::SACMODEL_CYLINDER:
156 case pcl::SACMODEL_NORMAL_PLANE:
157 case pcl::SACMODEL_NORMAL_PARALLEL_PLANE:
158 case pcl::SACMODEL_CONE:
159 case pcl::SACMODEL_NORMAL_SPHERE: {
160 pcl::SACSegmentationFromNormals<PointT, NormalT> seg;
161 seg.setOptimizeCoefficients(coefficients ?
true :
false);
166 cloudNormas->width * cloudNormas->height == 0) {
171 normalDisWeight > 0 ? normalDisWeight : 0.1 ;
172 seg.setModelType(modelType);
173 seg.setMethodType(methodType);
174 seg.setNormalDistanceWeight(normalWeight);
175 seg.setDistanceThreshold(distanceThreshold);
176 seg.setRadiusLimits(minRadiusLimits, maxRadiusLimits);
177 seg.setMaxIterations(maxIterations);
178 seg.setProbability(probability);
179 seg.setInputCloud(cloud);
180 seg.setInputNormals(cloudNormas);
183 seg.segment(*inliers, *coefficients);
185 pcl::ModelCoefficients coeff;
186 seg.segment(*inliers, coeff);
191 pcl::SACSegmentation<PointT> seg;
192 seg.setOptimizeCoefficients(coefficients ?
true :
false);
194 seg.setInputCloud(cloud);
195 seg.setModelType(modelType);
196 seg.setMethodType(methodType);
197 seg.setDistanceThreshold(distanceThreshold);
198 seg.setRadiusLimits(minRadiusLimits, maxRadiusLimits);
199 seg.setMaxIterations(maxIterations);
200 seg.setProbability(probability);
203 seg.segment(*inliers, *coefficients);
205 pcl::ModelCoefficients coeff;
206 seg.segment(*inliers, coeff);
221 int maxSearchLevel) {
223 pcl::search::KdTree<PointNT>::Ptr kdtree(
new pcl::search::KdTree<PointNT>);
224 kdtree->setInputCloud(cloudWithNormals);
227 pcl::GridProjection<PointNT> gp;
228 gp.setInputCloud(cloudWithNormals);
229 gp.setSearchMethod(kdtree);
230 gp.setResolution(
static_cast<double>(resolution));
231 gp.setPaddingSize(paddingSize);
232 gp.setMaxBinarySearchLevel(maxSearchLevel);
233 gp.reconstruct(outMesh);
242 int solverDivideDepth,
244 float samplesPerNode,
247 bool outputPolygons) {
249 pcl::search::KdTree<PointNT>::Ptr kdtree(
new pcl::search::KdTree<PointNT>);
250 kdtree->setInputCloud(cloudWithNormals);
251 pcl::Poisson<PointNT> pn;
252 pn.setConfidence(useConfidence);
253 pn.setDegree(degree);
254 pn.setDepth(treeDepth);
255 pn.setIsoDivide(isoDivideDepth);
256 pn.setManifold(useManifold);
257 pn.setOutputPolygons(outputPolygons);
258 pn.setSamplesPerNode(samplesPerNode);
261 pn.setSolverDivide(solverDivideDepth);
263 pn.setSearchMethod(kdtree);
264 pn.setInputCloud(cloudWithNormals);
265 pn.performReconstruction(outMesh);
272 int trigulationSearchRadius,
273 float weightingFactor,
274 int maxNearestNeighbors,
278 bool normalConsistency) {
280 pcl::search::KdTree<PointNT>::Ptr kdtree(
new pcl::search::KdTree<PointNT>);
281 kdtree->setInputCloud(cloudWithNormals);
282 pcl::GreedyProjectionTriangulation<PointNT> gp3;
284 gp3.setSearchRadius(trigulationSearchRadius);
285 gp3.setMu(
static_cast<double>(weightingFactor));
286 gp3.setMaximumNearestNeighbors(maxNearestNeighbors);
290 gp3.setNormalConsistency(normalConsistency);
291 gp3.setInputCloud(cloudWithNormals);
292 gp3.setSearchMethod(kdtree);
293 gp3.reconstruct(outMesh);
299 PointCloudT::Ptr &projectedCloud,
300 const pcl::ModelCoefficients::ConstPtr coefficients,
301 const int &modelType ) {
303 pcl::ProjectInliers<PointT> projectInliers;
305 projectInliers.setModelType(
static_cast<pcl::SacModel
>(modelType));
307 projectInliers.setInputCloud(originCloud);
309 projectInliers.setModelCoefficients(coefficients);
311 projectInliers.filter(*projectedCloud);
317 PointCloudT::Ptr &projectedCloud,
322 const int &modelType ) {
326 pcl::ModelCoefficients::Ptr coefficients(
new pcl::ModelCoefficients());
327 coefficients->values.resize(4);
328 coefficients->values[0] = coefficientA;
329 coefficients->values[1] = coefficientB;
330 coefficients->values[2] = coefficientC;
331 coefficients->values[3] = coefficientD;
333 return GetProjection(originCloud, projectedCloud, coefficients, modelType);
341 float gridResolution,
342 float percentageExtendGrid);
350 FeatureCloud::FeatureCloud()
352 m_normalRadius(0.02f),
353 m_featureRadius(0.02f),
354 m_maxThreadCount(QThread::idealThreadCount()) {}
359 pcl::io::loadPCDFile(pcd_file, *m_xyz);
372 pcl::FPFHEstimationOMP<PointT, NormalT, pcl::FPFHSignature33> fpfh_est;
373 fpfh_est.setNumberOfThreads(m_maxThreadCount);
374 fpfh_est.setInputCloud(m_xyz);
375 fpfh_est.setInputNormals(m_normals);
376 fpfh_est.setSearchMethod(m_searchMethod);
377 fpfh_est.setRadiusSearch(m_featureRadius);
378 fpfh_est.compute(*m_features);
388 : m_minSampleDistance(0.05f),
389 m_maxCorrespondenceDistance(0.01f * 0.01f),
390 m_nr_iterations(500) {
393 m_sac_ia.setMinSampleDistance(m_minSampleDistance);
394 m_sac_ia.setMaxCorrespondenceDistance(m_maxCorrespondenceDistance);
395 m_sac_ia.setMaximumIterations(m_nr_iterations);
400 m_target = target_cloud;
411 pcl::PointCloud<PointT> registration_output;
413 m_sac_ia.align(registration_output);
415 (
float)m_sac_ia.getFitnessScore(m_maxCorrespondenceDistance);
416 result.final_transformation = m_sac_ia.getFinalTransformation();
424 results.resize(m_templates.size());
425 for (std::size_t i = 0; i < m_templates.size(); ++i) {
426 align(m_templates[i], results[i]);
434 std::vector<Result, Eigen::aligned_allocator<Result>> results;
438 float lowest_score = std::numeric_limits<float>::infinity();
439 int best_template = 0;
440 for (std::size_t i = 0; i < results.size(); ++i) {
441 const Result &r = results[i];
444 best_template = (int)i;
449 result = results[best_template];
450 return (best_template);
461 const PointCloudT::ConstPtr inCloud,
462 CloudNormal::Ptr outcloud,
465 bool normalConsistency,
468 const PointCloudRGB::ConstPtr inCloud,
469 CloudNormal::Ptr outcloud,
472 bool normalConsistency,
475 const PointCloudRGBA::ConstPtr inCloud,
476 CloudNormal::Ptr outcloud,
479 bool normalConsistency,
482 const PointCloudT::ConstPtr inCloud,
483 PointCloudNormal::Ptr outcloud,
486 bool normalConsistency,
489 const PointCloudRGB::ConstPtr inCloud,
490 PointCloudNormal::Ptr outcloud,
493 bool normalConsistency,
496 const PointCloudRGBA::ConstPtr inCloud,
497 PointCloudNormal::Ptr outcloud,
500 bool normalConsistency,
504 const PCLCloud::ConstPtr inCloud,
505 PCLCloud::Ptr outCloud,
510 const PointCloudT::ConstPtr inCloud,
PCLMesh &outMesh,
int dimension);
512 const PointCloudRGB::ConstPtr inCloud,
PCLMesh &outMesh,
int dimension);
514 const PointCloudT::ConstPtr inCloud,
519 const PointCloudRGB::ConstPtr inCloud,
525 const PointCloudT::ConstPtr boundingBox,
526 PointCloudT::Ptr outCloud,
529 const PointCloudT::ConstPtr boundingBox,
530 PointCloudRGB::Ptr outCloud,
533 #if defined(WITH_PCL_NURBS)
534 template int NurbsSurfaceFitting<PointT>(
const PointCloudT::ConstPtr inCloud,
535 const NurbsParameters &nurbsParams,
537 PointCloudRGB::Ptr outCurve);
538 template int NurbsSurfaceFitting<PointRGB>(
539 const PointCloudRGB::ConstPtr inCloud,
540 const NurbsParameters &nurbsParams,
542 PointCloudRGB::Ptr outCurve);
544 template int BSplineCurveFitting3D<PointT>(
const PointCloudT::ConstPtr inCloud,
545 PointCloudRGB::Ptr outCurve,
547 int controlPointsNum,
548 unsigned curveResolution,
552 template int BSplineCurveFitting3D<PointRGB>(
553 const PointCloudRGB::ConstPtr inCloud,
554 PointCloudRGB::Ptr outCurve,
556 int controlPointsNum,
557 unsigned curveResolution,
561 template int BSplineCurveFitting2D<PointT>(
562 const PointCloudT::ConstPtr inCloud,
563 const CurveFittingMethod &fittingMethod,
564 PointCloudRGB::Ptr outCurve,
566 int controlPointsNum,
567 unsigned curveResolution,
571 template int BSplineCurveFitting2D<PointRGB>(
572 const PointCloudRGB::ConstPtr inCloud,
573 const CurveFittingMethod &fittingMethod,
574 PointCloudRGB::Ptr outCurve,
576 int controlPointsNum,
577 unsigned curveResolution,
584 const PointCloudT::ConstPtr inCloud,
585 std::vector<pcl::PointIndices> &cluster_indices,
586 float clusterTolerance ,
588 int maxClusterSize );
590 const PointCloudNormal::ConstPtr inCloud,
591 std::vector<pcl::PointIndices> &cluster_indices,
592 float clusterTolerance ,
594 int maxClusterSize );
597 pcl::PointIndicesPtr groundIndices,
600 float initialDistance,
603 const PointCloudRGB::ConstPtr inCloud,
604 pcl::PointIndicesPtr groundIndices,
607 float initialDistance,
611 const PointCloudNormal::ConstPtr inCloud,
613 PointCloudNormal::Ptr outCloud,
618 PointCloudNormal::Ptr &outcloud
619 #ifdef LP_PCL_PATCH_ENABLED
621 pcl::PointIndicesPtr &used_ids
625 template int EstimateSIFT<pcl::PointXYZI, PointT>(
626 const pcl::PointCloud<pcl::PointXYZI>::ConstPtr inCloud,
627 PointCloudT::Ptr outcloud,
630 int nr_scales_per_octave,
633 const PointCloudRGB::ConstPtr inCloud,
634 PointCloudT::Ptr outcloud,
637 int nr_scales_per_octave,
640 const PointCloudRGBA::ConstPtr inCloud,
641 PointCloudT::Ptr outcloud,
644 int nr_scales_per_octave,
647 template int EstimateShot<PointT, NormalT, pcl::SHOT352>(
648 const PointCloudT::ConstPtr inCloud,
649 const PointCloudT::ConstPtr keyPoints,
650 const CloudNormal::ConstPtr
normals,
651 pcl::PointCloud<pcl::SHOT352>::Ptr outDescriptors,
654 template int EstimateShot<PointRGB, NormalT, pcl::SHOT352>(
655 const PointCloudRGB::ConstPtr inCloud,
656 const PointCloudRGB::ConstPtr keyPoints,
657 const CloudNormal::ConstPtr
normals,
658 pcl::PointCloud<pcl::SHOT352>::Ptr outDescriptors,
661 template int EstimateShot<PointRGBA, NormalT, pcl::SHOT352>(
662 const PointCloudRGBA::ConstPtr inCloud,
663 const PointCloudRGBA::ConstPtr keyPoints,
664 const CloudNormal::ConstPtr
normals,
665 pcl::PointCloud<pcl::SHOT352>::Ptr outDescriptors,
670 const PointCloudT::ConstPtr inCloud,
671 const PointCloudNormal::ConstPtr normalsLargeScale,
672 const PointCloudNormal::ConstPtr normalsSmallScale,
673 PointCloudNormal::Ptr outCloud);
675 const PointCloudRGB::ConstPtr inCloud,
676 const PointCloudNormal::ConstPtr normalsLargeScale,
677 const PointCloudNormal::ConstPtr normalsSmallScale,
678 PointCloudNormal::Ptr outCloud);
680 template int EstimateLocalReferenceFrame<PointT, NormalT, pcl::ReferenceFrame>(
681 const PointCloudT::ConstPtr inCloud,
682 const PointCloudT::ConstPtr keyPoints,
683 const CloudNormal::ConstPtr
normals,
684 pcl::PointCloud<pcl::ReferenceFrame>::Ptr outRF,
687 EstimateLocalReferenceFrame<PointRGB, NormalT, pcl::ReferenceFrame>(
688 const PointCloudRGB::ConstPtr inCloud,
689 const PointCloudRGB::ConstPtr keyPoints,
690 const CloudNormal::ConstPtr
normals,
691 pcl::PointCloud<pcl::ReferenceFrame>::Ptr outRF,
694 EstimateLocalReferenceFrame<PointRGBA, NormalT, pcl::ReferenceFrame>(
695 const PointCloudRGBA::ConstPtr inCloud,
696 const PointCloudRGBA::ConstPtr keyPoints,
697 const CloudNormal::ConstPtr
normals,
698 pcl::PointCloud<pcl::ReferenceFrame>::Ptr outRF,
704 pcl::ReferenceFrame>(
705 const PointCloudT::ConstPtr modelKeypoints,
706 const PointCloudT::ConstPtr sceneKeypoints,
707 const pcl::PointCloud<pcl::ReferenceFrame>::ConstPtr modelRF,
708 const pcl::PointCloud<pcl::ReferenceFrame>::ConstPtr sceneRF,
709 const pcl::CorrespondencesConstPtr modelSceneCorrs,
710 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f>>
712 std::vector<pcl::Correspondences> &clusteredCorrs,
714 float houghThreshold);
718 pcl::ReferenceFrame>(
719 const PointCloudRGB::ConstPtr modelKeypoints,
720 const PointCloudRGB::ConstPtr sceneKeypoints,
721 const pcl::PointCloud<pcl::ReferenceFrame>::ConstPtr modelRF,
722 const pcl::PointCloud<pcl::ReferenceFrame>::ConstPtr sceneRF,
723 const pcl::CorrespondencesConstPtr modelSceneCorrs,
724 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f>>
726 std::vector<pcl::Correspondences> &clusteredCorrs,
728 float houghThreshold);
732 pcl::ReferenceFrame>(
733 const PointCloudRGBA::ConstPtr modelKeypoints,
734 const PointCloudRGBA::ConstPtr sceneKeypoints,
735 const pcl::PointCloud<pcl::ReferenceFrame>::ConstPtr modelRF,
736 const pcl::PointCloud<pcl::ReferenceFrame>::ConstPtr sceneRF,
737 const pcl::CorrespondencesConstPtr modelSceneCorrs,
738 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f>>
740 std::vector<pcl::Correspondences> &clusteredCorrs,
742 float houghThreshold);
745 const PointCloudT::ConstPtr modelKeypoints,
746 const PointCloudT::ConstPtr sceneKeypoints,
747 const pcl::CorrespondencesConstPtr modelSceneCorrs,
748 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f>>
750 std::vector<pcl::Correspondences> &clusteredCorrs,
754 const PointCloudRGB::ConstPtr modelKeypoints,
755 const PointCloudRGB::ConstPtr sceneKeypoints,
756 const pcl::CorrespondencesConstPtr modelSceneCorrs,
757 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f>>
759 std::vector<pcl::Correspondences> &clusteredCorrs,
763 const PointCloudRGBA::ConstPtr modelKeypoints,
764 const PointCloudRGBA::ConstPtr sceneKeypoints,
765 const pcl::CorrespondencesConstPtr modelSceneCorrs,
766 std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f>>
768 std::vector<pcl::Correspondences> &clusteredCorrs,
773 const PointCloudT::ConstPtr inCloud,
774 pcl::PointCloud<pcl::PointXYZI>::Ptr outcloud,
778 const PointCloudRGB::ConstPtr inCloud,
779 pcl::PointCloud<pcl::PointXYZI>::Ptr outcloud,
783 const PointCloudRGBA::ConstPtr inCloud,
784 pcl::PointCloud<pcl::PointXYZI>::Ptr outcloud,
789 PointCloudT::Ptr outcloud,
790 const float &searchRadius);
792 PointCloudRGB::Ptr outcloud,
793 const float &searchRadius);
795 const PointCloudRGBA::ConstPtr inCloud,
796 PointCloudRGBA::Ptr outcloud,
797 const float &searchRadius);
800 PointCloudT::Ptr outcloud,
801 const QString &filterFieldName,
802 const float &limit_min,
803 const float &limit_max);
805 PointCloudRGB::Ptr outcloud,
806 const QString &filterFieldName,
807 const float &limit_min,
808 const float &limit_max);
810 const PointCloudRGBA::ConstPtr inCloud,
811 PointCloudRGBA::Ptr outcloud,
812 const QString &filterFieldName,
813 const float &limit_min,
814 const float &limit_max);
817 PointCloudT::Ptr outcloud,
818 const float &leafSizeX,
819 const float &leafSizeY,
820 const float &leafSizeZ);
822 PointCloudRGB::Ptr outcloud,
823 const float &leafSizeX,
824 const float &leafSizeY,
825 const float &leafSizeZ);
827 PointCloudRGBA::Ptr outcloud,
828 const float &leafSizeX,
829 const float &leafSizeY,
830 const float &leafSizeZ);
833 const PointCloudT::ConstPtr inCloud,
834 const pcl::PointIndices::ConstPtr inliers,
835 PointCloudT::Ptr outcloud,
836 PointCloudT::Ptr outcloud2);
838 const PointCloudRGB::ConstPtr inCloud,
839 const pcl::PointIndices::ConstPtr inliers,
840 PointCloudRGB::Ptr outcloud,
841 PointCloudRGB::Ptr outcloud2);
843 const PointCloudRGBA::ConstPtr inCloud,
844 const pcl::PointIndices::ConstPtr inliers,
845 PointCloudRGBA::Ptr outcloud,
846 PointCloudRGBA::Ptr outcloud2);
849 const PointCloudT::ConstPtr inCloud,
850 std::vector<pcl::PointIndices> &outClusters,
851 PointCloudRGB::Ptr cloud_segmented,
852 const PointT foregroundPoint,
853 int neighboursNumber,
855 float backWeightRadius,
857 const pcl::IndicesConstPtr indices);
860 const PointCloudRGB::ConstPtr inCloud,
861 std::vector<pcl::PointIndices> &outClusters,
862 PointCloudRGB::Ptr cloud_segmented,
864 int neighboursNumber,
866 float backWeightRadius,
868 const pcl::IndicesConstPtr indices);
871 const PointCloudT::ConstPtr inCloud,
872 const CloudNormal::ConstPtr
normals,
873 PointCloudT::Ptr boundaryCloud,
874 const float angleThreshold,
878 const PointCloudT::ConstPtr inCloud,
879 const PointCloudNormal::ConstPtr
normals,
880 PointCloudT::Ptr boundaryCloud,
881 const float angleThreshold,
885 const PointCloudRGBA::ConstPtr inCloud,
886 const CloudNormal::ConstPtr
normals,
887 PointCloudRGBA::Ptr boundaryCloud,
888 const float angleThreshold,
892 const PointCloudRGBA::ConstPtr inCloud,
893 const PointCloudNormal::ConstPtr
normals,
894 PointCloudRGBA::Ptr boundaryCloud,
895 const float angleThreshold,
900 const PointCloudT::ConstPtr targetCloud,
902 PointCloudT::Ptr outRegistered,
903 int ipcMaxIterations,
904 float icpCorrDistance);
906 const PointCloudRGB::ConstPtr targetCloud,
908 PointCloudRGB::Ptr outRegistered,
909 int ipcMaxIterations,
910 float icpCorrDistance);
pcl::PointCloud< PointT > PointCloudT
pcl::PointXYZRGB PointRGB
pcl::PointXYZRGBA PointRGBA
pcl::PointCloud< NormalT > CloudNormal
static bool Print(const char *format,...)
Prints out a formatted message in console.
pcl::PointCloud< pcl::FPFHSignature33 > LocalFeatures
pcl::search::KdTree< PointT > SearchMethod
void computeLocalFeatures()
void computeSurfaceNormals()
pcl::PointCloud< NormalT > SurfaceNormals
void loadInputCloud(const std::string &pcd_file)
LocalFeatures::Ptr getLocalFeatures() const
PointCloudT::Ptr getPointCloud() const
void align(FeatureCloud &template_cloud, TemplateMatching::Result &result)
void setTargetCloud(FeatureCloud &target_cloud)
void alignAll(std::vector< TemplateMatching::Result, Eigen::aligned_allocator< Result >> &results)
int findBestAlignment(TemplateMatching::Result &result)
template int GetBoundaryCloud< PointT, PointNT >(const PointCloudT::ConstPtr inCloud, const PointCloudNormal::ConstPtr normals, PointCloudT::Ptr boundaryCloud, const float angleThreshold, const float radius, const bool useKnn)
template int PassThroughFilter< PointRGBA >(const PointCloudRGBA::ConstPtr inCloud, PointCloudRGBA::Ptr outcloud, const QString &filterFieldName, const float &limit_min, const float &limit_max)
template int GetMinCutSegmentation< PointT >(const PointCloudT::ConstPtr inCloud, std::vector< pcl::PointIndices > &outClusters, PointCloudRGB::Ptr cloud_segmented, const PointT foregroundPoint, int neighboursNumber, float smoothSigma, float backWeightRadius, float foreWeight, const pcl::IndicesConstPtr indices)
template int GetBoundaryCloud< PointRGBA, NormalT >(const PointCloudRGBA::ConstPtr inCloud, const CloudNormal::ConstPtr normals, PointCloudRGBA::Ptr boundaryCloud, const float angleThreshold, const float radius, const bool useKnn)
template int ComputeNormals< PointT, NormalT >(const PointCloudT::ConstPtr inCloud, CloudNormal::Ptr outcloud, const float radius, const bool useKnn, bool normalConsistency, int maxThreadCount)
template int EstimateSIFT< PointRGB, PointT >(const PointCloudRGB::ConstPtr inCloud, PointCloudT::Ptr outcloud, int nr_octaves, float min_scale, int nr_scales_per_octave, float min_contrast)
int GetGreedyTriangulation(const PointCloudNormal::ConstPtr &cloudWithNormals, PCLMesh &outMesh, int trigulationSearchRadius, float weightingFactor, int maxNearestNeighbors, int maxSurfaceAngle, int minAngle, int maxAngle, bool normalConsistency)
template int ProgressiveMpFilter< PointRGB >(const PointCloudRGB::ConstPtr inCloud, pcl::PointIndicesPtr groundIndices, int maxWindowSize, float slope, float initialDistance, float maxDistance)
template int ComputeNormals< PointRGBA, PointNT >(const PointCloudRGBA::ConstPtr inCloud, PointCloudNormal::Ptr outcloud, const float radius, const bool useKnn, bool normalConsistency, int maxThreadCount)
template int RemoveOutliersStatistical< PCLCloud >(const PCLCloud::ConstPtr inCloud, PCLCloud::Ptr outCloud, int knn, double nSigma)
template int ProgressiveMpFilter< PointT >(const PointCloudT::ConstPtr inCloud, pcl::PointIndicesPtr groundIndices, int maxWindowSize, float slope, float initialDistance, float maxDistance)
template int ExtractIndicesFilter< PointRGB >(const PointCloudRGB::ConstPtr inCloud, const pcl::PointIndices::ConstPtr inliers, PointCloudRGB::Ptr outcloud, PointCloudRGB::Ptr outcloud2)
int GetRegionGrowingRGB(const PointCloudRGB::ConstPtr cloud, std::vector< pcl::PointIndices > &clusters, PointCloudRGB::Ptr cloud_segmented, int min_cluster_size, float neighbors_distance, float point_color_diff, float region_color_diff)
Color based Region Growing.
template bool ICPRegistration< PointRGB, PointRGB >(const PointCloudRGB::ConstPtr targetCloud, const PointCloudRGB::ConstPtr sourceCloud, PointCloudRGB::Ptr outRegistered, int ipcMaxIterations, float icpCorrDistance)
int GetPoissonReconstruction(const PointCloudNormal::ConstPtr &cloudWithNormals, PCLMesh &outMesh, int degree, int treeDepth, int isoDivideDepth, int solverDivideDepth, float scale, float samplesPerNode, bool useConfidence, bool useManifold, bool outputPolygons)
template int GetUniformSampling< PointRGBA >(const PointCloudRGBA::ConstPtr inCloud, PointCloudRGBA::Ptr outcloud, const float &searchRadius)
template int ComputeNormals< PointRGB, PointNT >(const PointCloudRGB::ConstPtr inCloud, PointCloudNormal::Ptr outcloud, const float radius, const bool useKnn, bool normalConsistency, int maxThreadCount)
template int EstimateSIFT< PointRGBA, PointT >(const PointCloudRGBA::ConstPtr inCloud, PointCloudT::Ptr outcloud, int nr_octaves, float min_scale, int nr_scales_per_octave, float min_contrast)
int EstimateHough3DGrouping(const typename pcl::PointCloud< PointModelT >::ConstPtr modelKeypoints, const typename pcl::PointCloud< PointSceneT >::ConstPtr sceneKeypoints, const typename pcl::PointCloud< PointModelRfT >::ConstPtr modelRF, const typename pcl::PointCloud< PointSceneRfT >::ConstPtr sceneRF, const typename pcl::CorrespondencesConstPtr modelSceneCorrs, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f >> &rotoTranslations, std::vector< pcl::Correspondences > &clusteredCorrs, float houghBinSize=0.01f, float houghThreshold=5.0f)
template int ConditionalRemovalFilter< PointNT >(const PointCloudNormal::ConstPtr inCloud, const ConditionParameters ¶ms, PointCloudNormal::Ptr outCloud, bool keepOrganized)
template int EstimateGeometricConsistencyGrouping< PointRGBA, PointRGBA >(const PointCloudRGBA::ConstPtr modelKeypoints, const PointCloudRGBA::ConstPtr sceneKeypoints, const pcl::CorrespondencesConstPtr modelSceneCorrs, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f >> &rotoTranslations, std::vector< pcl::Correspondences > &clusteredCorrs, float gcSize, float gcThreshold)
int GetRegionGrowing(const PointCloudT::ConstPtr cloud, std::vector< pcl::PointIndices > &clusters, PointCloudRGB::Ptr cloud_segmented, int k, int min_cluster_size, int max_cluster_size, unsigned int neighbour_number, float smoothness_theta, float curvature)
Basic Region Growing.
template int VoxelGridFilter< PointRGBA >(const PointCloudRGBA::ConstPtr inCloud, PointCloudRGBA::Ptr outcloud, const float &leafSizeX, const float &leafSizeY, const float &leafSizeZ)
template int VoxelGridFilter< PointRGB >(const PointCloudRGB::ConstPtr inCloud, PointCloudRGB::Ptr outcloud, const float &leafSizeX, const float &leafSizeY, const float &leafSizeZ)
int GetSACSegmentation(const PointCloudT::ConstPtr cloud, pcl::PointIndices::Ptr inliers, pcl::ModelCoefficients::Ptr coefficients, const int &methodType, const int &modelType, float distanceThreshold, float probability, int maxIterations, float minRadiusLimits, float maxRadiusLimits, float normalDisWeight)
template int ComputeNormals< PointRGBA, NormalT >(const PointCloudRGBA::ConstPtr inCloud, CloudNormal::Ptr outcloud, const float radius, const bool useKnn, bool normalConsistency, int maxThreadCount)
template int GetMarchingCubes< PointNT >(const PointCloudNormal::ConstPtr inCloud, const MarchingMethod &marchingMethod, PCLMesh &outMesh, float epsilon, float isoLevel, float gridResolution, float percentageExtendGrid)
template int GetMinCutSegmentation< PointRGB >(const PointCloudRGB::ConstPtr inCloud, std::vector< pcl::PointIndices > &outClusters, PointCloudRGB::Ptr cloud_segmented, const PointRGB foregroundPoint, int neighboursNumber, float smoothSigma, float backWeightRadius, float foreWeight, const pcl::IndicesConstPtr indices)
template int GetUniformSampling< PointT >(const PointCloudT::ConstPtr inCloud, PointCloudT::Ptr outcloud, const float &searchRadius)
template int CropHullFilter< PointRGB >(const PointCloudRGB::ConstPtr inCloud, const PointCloudT::ConstPtr boundingBox, PointCloudRGB::Ptr outCloud, int dimensions)
template int ComputeNormals< PointT, PointNT >(const PointCloudT::ConstPtr inCloud, PointCloudNormal::Ptr outcloud, const float radius, const bool useKnn, bool normalConsistency, int maxThreadCount)
template int EstimateGeometricConsistencyGrouping< PointRGB, PointRGB >(const PointCloudRGB::ConstPtr modelKeypoints, const PointCloudRGB::ConstPtr sceneKeypoints, const pcl::CorrespondencesConstPtr modelSceneCorrs, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f >> &rotoTranslations, std::vector< pcl::Correspondences > &clusteredCorrs, float gcSize, float gcThreshold)
template int SmoothMls< PointT, PointNT >(const PointCloudT::ConstPtr &inCloud, const MLSParameters ¶ms, PointCloudNormal::Ptr &outcloud)
template int PassThroughFilter< PointT >(const PointCloudT::ConstPtr inCloud, PointCloudT::Ptr outcloud, const QString &filterFieldName, const float &limit_min, const float &limit_max)
template int GetConvexHullReconstruction< PointRGB >(const PointCloudRGB::ConstPtr inCloud, PCLMesh &outMesh, int dimension)
template int EstimateGeometricConsistencyGrouping< PointT, PointT >(const PointCloudT::ConstPtr modelKeypoints, const PointCloudT::ConstPtr sceneKeypoints, const pcl::CorrespondencesConstPtr modelSceneCorrs, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f >> &rotoTranslations, std::vector< pcl::Correspondences > &clusteredCorrs, float gcSize, float gcThreshold)
template int GetUniformSampling< PointRGB >(const PointCloudRGB::ConstPtr inCloud, PointCloudRGB::Ptr outcloud, const float &searchRadius)
template int GetConcaveHullReconstruction< PointT >(const PointCloudT::ConstPtr inCloud, PCLMesh &outMesh, int dimension, float alpha)
int GridProjection(const PointCloudNormal::ConstPtr &cloudWithNormals, PCLMesh &outMesh, float resolution, int paddingSize, int maxSearchLevel)
template int EstimateHarris3D< PointRGB >(const PointCloudRGB::ConstPtr inCloud, pcl::PointCloud< pcl::PointXYZI >::Ptr outcloud, float normalRadius, float searchRadius)
template int VoxelGridFilter< PointT >(const PointCloudT::ConstPtr inCloud, PointCloudT::Ptr outcloud, const float &leafSizeX, const float &leafSizeY, const float &leafSizeZ)
template int GetConcaveHullReconstruction< PointRGB >(const PointCloudRGB::ConstPtr inCloud, PCLMesh &outMesh, int dimension, float alpha)
template int CropHullFilter< PointT >(const PointCloudT::ConstPtr inCloud, const PointCloudT::ConstPtr boundingBox, PointCloudT::Ptr outCloud, int dimensions)
template int EuclideanCluster< PointNT >(const PointCloudNormal::ConstPtr inCloud, std::vector< pcl::PointIndices > &cluster_indices, float clusterTolerance, int minClusterSize, int maxClusterSize)
template int EuclideanCluster< PointT >(const PointCloudT::ConstPtr inCloud, std::vector< pcl::PointIndices > &cluster_indices, float clusterTolerance, int minClusterSize, int maxClusterSize)
template int ComputeNormals< PointRGB, NormalT >(const PointCloudRGB::ConstPtr inCloud, CloudNormal::Ptr outcloud, const float radius, const bool useKnn, bool normalConsistency, int maxThreadCount)
template int GetBoundaryCloud< PointT, NormalT >(const PointCloudT::ConstPtr inCloud, const CloudNormal::ConstPtr normals, PointCloudT::Ptr boundaryCloud, const float angleThreshold, const float radius, const bool useKnn)
template int GetConvexHullReconstruction< PointT >(const PointCloudT::ConstPtr inCloud, PCLMesh &outMesh, int dimension)
template bool ICPRegistration< PointT, PointT >(const PointCloudT::ConstPtr targetCloud, const PointCloudT::ConstPtr sourceCloud, PointCloudT::Ptr outRegistered, int ipcMaxIterations, float icpCorrDistance)
template int EstimateHarris3D< PointRGBA >(const PointCloudRGBA::ConstPtr inCloud, pcl::PointCloud< pcl::PointXYZI >::Ptr outcloud, float normalRadius, float searchRadius)
template int ExtractIndicesFilter< PointT >(const PointCloudT::ConstPtr inCloud, const pcl::PointIndices::ConstPtr inliers, PointCloudT::Ptr outcloud, PointCloudT::Ptr outcloud2)
int GetProjection(const PointCloudT::ConstPtr &originCloud, PointCloudT::Ptr &projectedCloud, const pcl::ModelCoefficients::ConstPtr coefficients, const int &modelType)
template int DONEstimation< PointRGB, PointNT, PointNT >(const PointCloudRGB::ConstPtr inCloud, const PointCloudNormal::ConstPtr normalsLargeScale, const PointCloudNormal::ConstPtr normalsSmallScale, PointCloudNormal::Ptr outCloud)
template int PassThroughFilter< PointRGB >(const PointCloudRGB::ConstPtr inCloud, PointCloudRGB::Ptr outcloud, const QString &filterFieldName, const float &limit_min, const float &limit_max)
template int EstimateHarris3D< PointT >(const PointCloudT::ConstPtr inCloud, pcl::PointCloud< pcl::PointXYZI >::Ptr outcloud, float normalRadius, float searchRadius)
template int DONEstimation< PointT, PointNT, PointNT >(const PointCloudT::ConstPtr inCloud, const PointCloudNormal::ConstPtr normalsLargeScale, const PointCloudNormal::ConstPtr normalsSmallScale, PointCloudNormal::Ptr outCloud)
template int ExtractIndicesFilter< PointRGBA >(const PointCloudRGBA::ConstPtr inCloud, const pcl::PointIndices::ConstPtr inliers, PointCloudRGBA::Ptr outcloud, PointCloudRGBA::Ptr outcloud2)
template int GetBoundaryCloud< PointRGBA, PointNT >(const PointCloudRGBA::ConstPtr inCloud, const PointCloudNormal::ConstPtr normals, PointCloudRGBA::Ptr boundaryCloud, const float angleThreshold, const float radius, const bool useKnn)
float DegreesToRadians(int degrees)
Convert degrees to radians.