Point Cloud Library (PCL)
1.11.0
|
42 #include <pcl/recognition/cg/correspondence_grouping.h>
43 #include <pcl/point_cloud.h>
53 template<
typename Po
intModelT,
typename Po
intSceneT>
116 recognize (std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > &transformations);
126 recognize (std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > &transformations, std::vector<pcl::Correspondences> &clustered_corrs);
152 #ifdef PCL_NO_PRECOMPILE
153 #include <pcl/recognition/impl/cg/geometric_consistency.hpp>
typename SceneCloud::ConstPtr SceneCloudConstPtr
GeometricConsistencyGrouping()
Constructor.
typename PointCloud::ConstPtr PointCloudConstPtr
void clusterCorrespondences(std::vector< Correspondences > &model_instances) override
Cluster the input correspondences in order to distinguish between different instances of the model in...
bool recognize(std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &transformations)
The main function, recognizes instances of the model into the scene set by the user.
double getGCSize() const
Gets the consensus set resolution.
int getGCThreshold() const
Gets the minimum cluster size.
PointCloud represents the base class in PCL for storing collections of 3D points.
int gc_threshold_
Minimum cluster size.
std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > found_transformations_
Transformations found by clusterCorrespondences method.
double gc_size_
Resolution of the consensus set used to cluster correspondences together.
Class implementing a 3D correspondence grouping enforcing geometric consistency among feature corresp...
typename PointCloud::Ptr PointCloudPtr
shared_ptr< PointCloud< PointT > > Ptr
Abstract base class for Correspondence Grouping algorithms.
shared_ptr< const PointCloud< PointT > > ConstPtr
void setGCThreshold(int threshold)
Sets the minimum cluster size.
void setGCSize(double gc_size)
Sets the consensus set resolution.