Point Cloud Library (PCL)
1.9.1
|
44 #include <pcl/registration/icp.h>
45 #include <pcl/registration/bfgs.h>
59 template <
typename Po
intSource,
typename Po
intTarget>
93 typedef std::vector< Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d> >
MatricesVector;
100 typedef boost::shared_ptr< GeneralizedIterativeClosestPoint<PointSource, PointTarget> >
Ptr;
101 typedef boost::shared_ptr< const GeneralizedIterativeClosestPoint<PointSource, PointTarget> >
ConstPtr;
115 reg_name_ =
"GeneralizedIterativeClosestPoint";
121 this, _1, _2, _3, _4, _5);
131 if (cloud->points.empty ())
133 PCL_ERROR (
"[pcl::%s::setInputSource] Invalid or empty point cloud dataset given!\n",
getClassName ().c_str ());
138 for (
size_t i = 0; i < input.
size (); ++i)
139 input[i].data[3] = 1.0;
187 const std::vector<int> &indices_src,
189 const std::vector<int> &indices_tgt,
190 Eigen::Matrix4f &transformation_matrix);
301 template<
typename Po
intT>
314 size_t n = mat1.rows();
316 for(
size_t i = 0; i < n; i++)
317 for(
size_t j = 0; j < n; j++)
318 r += mat1 (j, i) * mat2 (i,j);
359 const std::vector<int> &src_indices,
361 const std::vector<int> &tgt_indices,
366 #include <pcl/registration/impl/gicp.hpp>
368 #endif //#ifndef PCL_GICP_H_
void computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const
Computes rotation matrix derivative.
MatricesVectorPtr target_covariances_
Target cloud points covariances.
This file defines compatibility wrappers for low level I/O functions.
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)
boost::shared_ptr< PointCloud< PointSource > > Ptr
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)
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...
Registration< PointSource, PointTarget >::KdTreePtr InputKdTreePtr
void applyState(Eigen::Matrix4f &t, const Vector6d &x) const
compute transformation matrix from transformation matrix
PointIndices::Ptr PointIndicesPtr
double corr_dist_threshold_
The maximum distance threshold between two correspondent points in source <-> target.
IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm.
boost::shared_ptr< MatricesVector > MatricesVectorPtr
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 min_number_correspondences_
The minimum number of correspondences that the algorithm needs before attempting to estimate the tran...
virtual void setInputTarget(const PointCloudTargetConstPtr &cloud)
Provide a pointer to the input target (e.g., the point cloud that we want to align to the target)
int max_inner_iterations_
maximum number of optimizations
pcl::PointCloud< PointSource > PointCloudSource
boost::shared_ptr< ::pcl::PointIndices > Ptr
void setInputTarget(const PointCloudTargetConstPtr &target)
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
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.
PointIndices::ConstPtr PointIndicesConstPtr
boost::shared_ptr< KdTree< PointT, Tree > > Ptr
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.
const std::vector< int > * tmp_idx_tgt_
Temporary pointer to the target dataset indices.
optimization functor structure
void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess)
Rigid transformation computation method with initial guess.
boost::shared_ptr< const GeneralizedIterativeClosestPoint< PointSource, PointTarget > > ConstPtr
boost::shared_ptr< GeneralizedIterativeClosestPoint< PointSource, PointTarget > > Ptr
Eigen::Matrix< double, 6, 1 > Vector6d
void fdf(const Vector6d &x, double &f, Vector6d &df)
void setInputSource(const PointCloudSourceConstPtr &cloud)
Provide a pointer to the input dataset.
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!).
boost::shared_ptr< const MatricesVector > MatricesVectorConstPtr
Registration< PointSource, PointTarget >::KdTree InputKdTree
double matricesInnerProd(const Eigen::MatrixXd &mat1, const Eigen::MatrixXd &mat2) const
boost::shared_ptr< ::pcl::PointIndices const > ConstPtr
PointCloudSource::ConstPtr PointCloudSourceConstPtr
double rotation_epsilon_
The epsilon constant for rotation error.
PointCloudTarget::ConstPtr PointCloudTargetConstPtr
boost::shared_ptr< const PointCloud< PointSource > > ConstPtr
int getCorrespondenceRandomness()
Get the number of neighbors used when computing covariances as set by the user.
double getRotationEpsilon()
Get the rotation epsilon (maximum allowable difference between two consecutive rotations) as set by t...
boost::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_
const Eigen::Matrix3d & mahalanobis(size_t index) const
PointCloudTarget::Ptr PointCloudTargetPtr
void df(const Vector6d &x, Vector6d &df)
double operator()(const Vector6d &x)
PointCloudSource::Ptr PointCloudSourcePtr
const std::vector< int > * tmp_idx_src_
Temporary pointer to the source dataset indices.
const GeneralizedIterativeClosestPoint * gicp_
MatricesVectorPtr input_covariances_
Input cloud points covariances.
int getMaximumOptimizerIterations()
void setMaximumOptimizerIterations(int max)
set maximum number of iterations at the optimization step
std::vector< Eigen::Matrix3d > mahalanobis_
Mahalanobis matrices holder.
GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest ...
std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > MatricesVector
pcl::PointCloud< PointTarget > PointCloudTarget
int k_correspondences_
The number of neighbors used for covariances computation.
std::string reg_name_
The registration method name.
GeneralizedIterativeClosestPoint()
Empty constructor.