44 #include <pcl/registration/correspondence_estimation.h>
45 #include <pcl/registration/correspondence_rejection.h>
46 #include <pcl/registration/transformation_estimation.h>
47 #include <pcl/search/kdtree.h>
49 #include <pcl/pcl_base.h>
56 template <
typename Po
intSource,
typename Po
intTarget,
typename Scalar =
float>
59 using Matrix4 = Eigen::Matrix<Scalar, 4, 4>;
66 using Ptr = shared_ptr<Registration<PointSource, PointTarget, Scalar>>;
67 using ConstPtr = shared_ptr<const Registration<PointSource, PointTarget, Scalar>>;
87 TransformationEstimation<PointSource, PointTarget, Scalar>;
121 , point_representation_()
240 bool force_no_recompute =
false)
424 point_representation_ = point_representation;
433 std::function<UpdateVisualizerCallbackSignature>& visualizerCallback)
435 if (visualizerCallback) {
449 getFitnessScore(
double max_range = std::numeric_limits<double>::max());
459 const std::vector<float>& distances_b);
484 inline const std::string&
521 inline std::vector<CorrespondenceRejectorPtr>
666 std::vector<float>& distances)
668 int k =
tree_->nearestKSearch(cloud, index, 1, indices, distances);
690 PCL_WARN(
"[pcl::registration::Registration] setInputCloud is deprecated."
691 "Please use setInputSource instead.\n");
700 #include <pcl/registration/impl/registration.hpp>
PointCloudConstPtr input_
The input point cloud dataset.
shared_ptr< PointCloud< PointSource > > Ptr
shared_ptr< const PointCloud< PointSource > > ConstPtr
Registration represents the base registration class for general purpose, ICP-like methods.
bool target_cloud_updated_
Variable that stores whether we have a new target cloud, meaning we need to pre-process it again.
Matrix4 final_transformation_
The final transformation matrix estimated by the registration method after N iterations.
typename KdTreeReciprocal::Ptr KdTreeReciprocalPtr
bool initCompute()
Internal computation initialization.
std::function< UpdateVisualizerCallbackSignature > update_visualizer_
Callback function to update intermediate source point cloud position during it's registration to the ...
virtual void setInputSource(const PointCloudSourceConstPtr &cloud)
Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
double corr_dist_threshold_
The maximum distance threshold between two correspondent points in source <-> target.
void clearCorrespondenceRejectors()
Clear the list of correspondence rejectors.
double getTransformationEpsilon()
Get the transformation epsilon (maximum allowable translation squared difference between two consecut...
void(const pcl::PointCloud< PointSource > &, const pcl::Indices &, const pcl::PointCloud< PointTarget > &, const pcl::Indices &) UpdateVisualizerCallbackSignature
The callback signature to the function updating intermediate source point cloud position during it's ...
std::string reg_name_
The registration method name.
Matrix4 getFinalTransformation()
Get the final transformation matrix estimated by the registration method.
void setRANSACIterations(int ransac_iterations)
Set the number of iterations RANSAC should run for.
const std::string & getClassName() const
Abstract class get name method.
shared_ptr< const Registration< PointSource, PointTarget, Scalar > > ConstPtr
Matrix4 transformation_
The transformation matrix estimated by the registration method.
pcl::PointCloud< PointSource > PointCloudSource
KdTreeReciprocalPtr tree_reciprocal_
A pointer to the spatial search object of the source.
bool removeCorrespondenceRejector(unsigned int i)
Remove the i-th correspondence rejector in the list.
void setCorrespondenceEstimation(const CorrespondenceEstimationPtr &ce)
Provide a pointer to the correspondence estimation object.
typename CorrespondenceEstimation::ConstPtr CorrespondenceEstimationConstPtr
void setMaximumIterations(int nr_iterations)
Set the maximum number of iterations the internal optimization should run for.
void setSearchMethodSource(const KdTreeReciprocalPtr &tree, bool force_no_recompute=false)
Provide a pointer to the search object used to find correspondences in the source cloud (usually used...
void setSearchMethodTarget(const KdTreePtr &tree, bool force_no_recompute=false)
Provide a pointer to the search object used to find correspondences in the target cloud.
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
typename KdTree::Ptr KdTreePtr
virtual void setInputTarget(const PointCloudTargetConstPtr &cloud)
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
bool registerVisualizationCallback(std::function< UpdateVisualizerCallbackSignature > &visualizerCallback)
Register the user callback function which will be called from registration thread in order to update ...
typename TransformationEstimation::Ptr TransformationEstimationPtr
typename PointCloudSource::Ptr PointCloudSourcePtr
void setPointRepresentation(const PointRepresentationConstPtr &point_representation)
Provide a boost shared pointer to the PointRepresentation to be used when comparing points.
CorrespondenceEstimationPtr correspondence_estimation_
A CorrespondenceEstimation object, used to estimate correspondences between the source and the target...
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
double getTransformationRotationEpsilon()
Get the transformation rotation epsilon (maximum allowable difference between two consecutive transfo...
bool force_no_recompute_
A flag which, if set, means the tree operating on the target cloud will never be recomputed.
void setRANSACOutlierRejectionThreshold(double inlier_threshold)
Set the inlier distance threshold for the internal RANSAC outlier rejection loop.
void setMaxCorrespondenceDistance(double distance_threshold)
Set the maximum distance threshold between two correspondent points in source <-> target.
void addCorrespondenceRejector(const CorrespondenceRejectorPtr &rejector)
Add a new correspondence rejector to the list.
int nr_iterations_
The number of iterations the internal optimization ran for (used internally).
shared_ptr< Registration< PointSource, PointTarget, Scalar > > Ptr
double getRANSACOutlierRejectionThreshold()
Get the inlier distance threshold for the internal outlier rejection loop as set by the user.
double getEuclideanFitnessEpsilon()
Get the maximum allowed distance error before the algorithm will be considered to have converged,...
double getMaxCorrespondenceDistance()
Get the maximum distance threshold between two correspondent points in source <-> target.
KdTreePtr getSearchMethodTarget() const
Get a pointer to the search method used to find correspondences in the target cloud.
KdTreePtr tree_
A pointer to the spatial search object.
Registration()
Empty constructor.
Matrix4 getLastIncrementalTransformation()
Get the last incremental transformation matrix estimated by the registration method.
typename PointCloudTarget::Ptr PointCloudTargetPtr
Matrix4 previous_transformation_
The previous transformation matrix estimated by the registration method (used internally).
bool converged_
Holds internal convergence state, given user parameters.
int ransac_iterations_
The number of iterations RANSAC should run for.
Eigen::Matrix< Scalar, 4, 4 > Matrix4
void align(PointCloudSource &output)
Call the registration algorithm which estimates the transformation and returns the transformed source...
PointCloudTargetConstPtr const getInputTarget()
Get a pointer to the input point cloud dataset target.
CorrespondencesPtr correspondences_
The set of correspondences determined at this ICP step.
TransformationEstimationPtr transformation_estimation_
A TransformationEstimation object, used to calculate the 4x4 rigid transformation.
bool searchForNeighbors(const PointCloudSource &cloud, int index, pcl::Indices &indices, std::vector< float > &distances)
Search for the closest nearest neighbor of a given point.
int max_iterations_
The maximum number of iterations the internal optimization should run for.
double transformation_rotation_epsilon_
The maximum rotation difference between two consecutive transformations in order to consider converge...
unsigned int min_number_correspondences_
The minimum number of correspondences that the algorithm needs before attempting to estimate the tran...
double getFitnessScore(double max_range=std::numeric_limits< double >::max())
Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target)
double euclidean_fitness_epsilon_
The maximum allowed Euclidean error between two consecutive steps in the ICP loop,...
double inlier_threshold_
The inlier distance threshold for the internal RANSAC outlier rejection loop.
pcl::registration::CorrespondenceRejector::Ptr CorrespondenceRejectorPtr
std::vector< CorrespondenceRejectorPtr > getCorrespondenceRejectors()
Get the list of correspondence rejectors.
PointCloudSourceConstPtr const getInputSource()
Get a pointer to the input point cloud dataset target.
typename TransformationEstimation::ConstPtr TransformationEstimationConstPtr
typename pcl::registration::TransformationEstimation< PointSource, PointTarget, Scalar > TransformationEstimation
bool hasConverged() const
Return the state of convergence after the last align run.
typename KdTree::PointRepresentationConstPtr PointRepresentationConstPtr
void setTransformationEstimation(const TransformationEstimationPtr &te)
Provide a pointer to the transformation estimation object.
bool force_no_recompute_reciprocal_
A flag which, if set, means the tree operating on the source cloud will never be recomputed.
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
std::vector< CorrespondenceRejectorPtr > correspondence_rejectors_
The list of correspondence rejectors to use.
KdTreeReciprocalPtr getSearchMethodSource() const
Get a pointer to the search method used to find correspondences in the source cloud.
~Registration() override=default
destructor.
int getMaximumIterations()
Get the maximum number of iterations the internal optimization should run for, as set by the user.
void setTransformationRotationEpsilon(double epsilon)
Set the transformation rotation epsilon (maximum allowable rotation difference between two consecutiv...
bool initComputeReciprocal()
Internal computation when reciprocal lookup is needed.
virtual void computeTransformation(PointCloudSource &output, const Matrix4 &guess)=0
Abstract transformation computation method with initial guess.
typename CorrespondenceEstimation::Ptr CorrespondenceEstimationPtr
void setEuclideanFitnessEpsilon(double epsilon)
Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop,...
void setTransformationEpsilon(double epsilon)
Set the transformation epsilon (maximum allowable translation squared difference between two consecut...
bool source_cloud_updated_
Variable that stores whether we have a new source cloud, meaning we need to pre-process it again.
PointCloudTargetConstPtr target_
The input point cloud dataset target.
double getRANSACIterations()
Get the number of iterations RANSAC should run for, as set by the user.
Abstract CorrespondenceEstimationBase class.
shared_ptr< const CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > ConstPtr
shared_ptr< CorrespondenceEstimationBase< PointSource, PointTarget, Scalar > > Ptr
shared_ptr< CorrespondenceRejector > Ptr
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
shared_ptr< KdTree< PointT, Tree > > Ptr
typename PointRepresentation< PointT >::ConstPtr PointRepresentationConstPtr
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Defines functions, macros and traits for allocating and using memory.
shared_ptr< Correspondences > CorrespondencesPtr
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
IndicesAllocator<> Indices
Type used for indices in PCL.
Defines all the PCL and non-PCL macros used.