Point Cloud Library (PCL)
1.11.1-dev
|
43 #include <pcl/registration/bfgs.h>
44 #include <pcl/registration/icp.h>
57 template <
typename Po
intSource,
typename Po
intTarget>
92 std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d>>;
99 using Ptr = shared_ptr<GeneralizedIterativeClosestPoint<PointSource, PointTarget>>;
101 shared_ptr<const GeneralizedIterativeClosestPoint<PointSource, PointTarget>>;
116 reg_name_ =
"GeneralizedIterativeClosestPoint";
121 const std::vector<int>& indices_src,
123 const std::vector<int>& indices_tgt,
124 Eigen::Matrix4f& transformation_matrix) {
126 cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix);
137 if (cloud->points.empty()) {
139 "[pcl::%s::setInputSource] Invalid or empty point cloud dataset given!\n",
145 for (std::size_t i = 0; i < input.
size(); ++i)
146 input[i].data[3] = 1.0;
196 const std::vector<int>& indices_src,
198 const std::vector<int>& indices_tgt,
199 Eigen::Matrix4f& transformation_matrix);
202 inline const Eigen::Matrix3d&
369 template <
typename Po
intT>
383 std::size_t n = mat1.rows();
385 for (std::size_t i = 0; i < n; i++)
386 for (std::size_t j = 0; j < n; j++)
387 r += mat1(j, i) * mat2(i, j);
398 const Eigen::Matrix4f& guess)
override;
407 std::vector<int>& index,
438 const std::vector<int>& src_indices,
440 const std::vector<int>& tgt_indices,
441 Eigen::Matrix4f& transformation_matrix)>
446 #include <pcl/registration/impl/gicp.hpp>
void computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const
Computes rotation matrix derivative.
MatricesVectorPtr target_covariances_
Target cloud points covariances.
void setInputSource(const PointCloudSourceConstPtr &cloud) override
Provide a pointer to the input dataset.
Eigen::Matrix4f base_transformation_
base transformation
void setRotationEpsilon(double epsilon)
Set the rotation epsilon (maximum allowable difference between two consecutive rotations) in order fo...
Registration represents the base registration class for general purpose, ICP-like methods.
float distance(const PointT &p1, const PointT &p2)
Eigen::Matrix< double, 6, 1 > Vector6d
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
double gicp_epsilon_
The epsilon constant for gicp paper; this is NOT the convergence tolerance default: 0....
void estimateRigidTransformationBFGS(const PointCloudSource &cloud_src, const std::vector< int > &indices_src, const PointCloudTarget &cloud_tgt, const std::vector< int > &indices_tgt, Eigen::Matrix4f &transformation_matrix)
Estimate a rigid rotation transformation between a source and a target point cloud using an iterative...
void applyState(Eigen::Matrix4f &t, const Vector6d &x) const
compute transformation matrix from transformation matrix
typename Registration< PointSource, PointTarget >::KdTree InputKdTree
double corr_dist_threshold_
The maximum distance threshold between two correspondent points in source <-> target.
double getRotationEpsilon() const
Get the rotation epsilon (maximum allowable difference between two consecutive rotations) as set by t...
const Eigen::Matrix3d & mahalanobis(std::size_t index) const
IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm.
shared_ptr< GeneralizedIterativeClosestPoint< PointSource, PointTarget > > Ptr
KdTreePtr tree_
A pointer to the spatial search object.
void setSourceCovariances(const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input source (if computed externally!).
const std::string & getClassName() const
Abstract class get name method.
int max_iterations_
The maximum number of iterations the internal optimization should run for.
int getMaximumOptimizerIterations() const
Return maximum number of iterations at the optimization step.
int min_number_correspondences_
The minimum number of correspondences that the algorithm needs before attempting to estimate the tran...
void setInputSource(const PointCloudSourceConstPtr &cloud) override
Provide a pointer to the input source (e.g., the point cloud that we want to align to the target)
void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess) override
Rigid transformation computation method with initial guess.
shared_ptr< const GeneralizedIterativeClosestPoint< PointSource, PointTarget > > ConstPtr
shared_ptr< MatricesVector > MatricesVectorPtr
void setInputTarget(const PointCloudTargetConstPtr &target) override
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
int max_inner_iterations_
maximum number of optimizations
int getCorrespondenceRandomness() const
Get the number of neighbors used when computing covariances as set by the user.
pcl::PointCloud< PointTarget > PointCloudTarget
PointIndices::Ptr PointIndicesPtr
void setTranslationGradientTolerance(double tolerance)
Set the minimal translation gradient threshold for early optimization stop.
shared_ptr< KdTree< PointT, Tree > > Ptr
void setCorrespondenceRandomness(int k)
Set the number of neighbors used when selecting a point neighbourhood to compute covariances.
const PointCloudSource * tmp_src_
Temporary pointer to the source dataset.
bool searchForNeighbors(const PointSource &query, std::vector< int > &index, std::vector< float > &distance)
Search for the closest nearest neighbor of a given point.
std::function< void(const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &src_indices, const pcl::PointCloud< PointTarget > &cloud_tgt, const std::vector< int > &tgt_indices, Eigen::Matrix4f &transformation_matrix)> rigid_transformation_estimation_
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
const PointCloudTarget * tmp_tgt_
Temporary pointer to the target dataset.
shared_ptr< const ::pcl::PointIndices > ConstPtr
const std::vector< int > * tmp_idx_tgt_
Temporary pointer to the target dataset indices.
optimization functor structure
void setInputTarget(const PointCloudTargetConstPtr &cloud) override
Provide a pointer to the input target (e.g., the point cloud that we want to align to the target)
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
pcl::PointCloud< PointSource > PointCloudSource
double operator()(const Vector6d &x) override
typename Registration< PointSource, PointTarget >::KdTreePtr InputKdTreePtr
OptimizationFunctorWithIndices(const GeneralizedIterativeClosestPoint *gicp)
void computeCovariances(typename pcl::PointCloud< PointT >::ConstPtr cloud, const typename pcl::search::KdTree< PointT >::Ptr tree, MatricesVector &cloud_covariances)
compute points covariances matrices according to the K nearest neighbors.
void setTargetCovariances(const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input target (if computed externally!).
double getTranslationGradientTolerance() const
Return the minimal translation gradient threshold for early optimization stop.
double translation_gradient_tolerance_
minimal translation gradient for early optimization stop
shared_ptr< ::pcl::PointIndices > Ptr
double rotation_gradient_tolerance_
minimal rotation gradient for early optimization stop
double matricesInnerProd(const Eigen::MatrixXd &mat1, const Eigen::MatrixXd &mat2) const
double rotation_epsilon_
The epsilon constant for rotation error.
shared_ptr< PointCloud< PointSource > > Ptr
typename PointCloudTarget::Ptr PointCloudTargetPtr
PointIndices::ConstPtr PointIndicesConstPtr
shared_ptr< const PointCloud< PointSource > > ConstPtr
const std::vector< int > * tmp_idx_src_
Temporary pointer to the source dataset indices.
const GeneralizedIterativeClosestPoint * gicp_
std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > MatricesVector
void df(const Vector6d &x, Vector6d &df) override
MatricesVectorPtr input_covariances_
Input cloud points covariances.
double getRotationGradientTolerance() const
Return the minimal rotation gradient threshold for early optimization stop.
void setMaximumOptimizerIterations(int max)
Set maximum number of iterations at the optimization step.
std::vector< Eigen::Matrix3d > mahalanobis_
Mahalanobis matrices holder.
BFGSSpace::Status checkGradient(const Vector6d &g) override
typename PointCloudSource::Ptr PointCloudSourcePtr
shared_ptr< const MatricesVector > MatricesVectorConstPtr
GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest ...
int k_correspondences_
The number of neighbors used for covariances computation.
std::string reg_name_
The registration method name.
void setRotationGradientTolerance(double tolerance)
Set the minimal rotation gradient threshold for early optimization stop.
GeneralizedIterativeClosestPoint()
Empty constructor.
void fdf(const Vector6d &x, double &f, Vector6d &df) override