#include <transformation_estimation_wdf.h>
Classes | |
struct | Functor |
struct | OptimizationFunctor |
struct | OptimizationFunctorWithWeights |
Public Member Functions | |
void | estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &indices_src, const std::vector< int > &indices_src_dfp, const pcl::PointCloud< PointTarget > &cloud_tgt, const std::vector< int > &indices_tgt, const std::vector< int > &indices_tgt_dfp, float alpha_arg, Eigen::Matrix4f &transformation_matrix) |
Estimate a rigid rotation transformation between a source and a target point cloud using WDF. | |
void | estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, const pcl::Correspondences &correspondences, const pcl::Correspondences &correspondences_dfp, float alpha_arg, Eigen::Matrix4f &transformation_matrix) |
Estimate a rigid rotation transformation between a source and a target point cloud using WDF. | |
void | estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &indices_src, const pcl::PointCloud< PointTarget > &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 WDF. This method has to be used in conjunction with methods setCorrespondecesDFP and setAlpha. In this manner it can be combined with pcl::IterativeClosestPoint via setTransformationEstimation method. | |
float | getAlpha (void) |
float | getBeta (void) |
void | setAlpha (float alpha_arg) |
void | setBeta (float alpha_arg) |
void | setCorrespondecesDFP (pcl::Correspondences correspondences_dfp) |
Set correspondences between source and target cloud distinctive feature points. This has to be set when using this class with pcl::IterativeClosestPoint. | |
void | setCorrespondecesDFP (std::vector< int > &indices_src_dfp_arg, std::vector< int > &indices_tgt_dfp_arg) |
Set correspondences between source and target cloud distinctive feature points. This has to be set when using this class with pcl::IterativeClosestPoint. | |
void | setWarpFunction (const boost::shared_ptr< pcl::WarpPointRigid< PointSource, PointTarget > > &warp_fcn) |
Set the function we use to warp points. Defaults to rigid 6D warp. | |
void | setWeightsDFP (std::vector< float > weights_dfp_arg) |
TransformationEstimationWDF () | |
virtual | ~TransformationEstimationWDF () |
Protected Member Functions | |
virtual double | computeDistance (const PointSource &p_src, const PointTarget &p_tgt) |
Compute the distance between a source point and its corresponding target point. | |
virtual double | computeDistancePointToPlane (const PointSource &p_src, const PointTarget &p_tgt) |
virtual double | computeDistanceWeight (const double &depth) |
Protected Attributes | |
const std::vector< float > * | tmp_dfp_weights_ |
Temporary pointer to weights of distinctive feature point pairs. | |
const std::vector< int > * | tmp_idx_src_ |
Temporary pointer to the source dataset indices. | |
const std::vector< int > * | tmp_idx_src_dfp_ |
Temporary pointer to the source dataset distinctive feature point indices. | |
const std::vector< int > * | tmp_idx_tgt_ |
Temporary pointer to the target dataset indices. | |
const std::vector< int > * | tmp_idx_tgt_dfp_ |
Temporary pointer to the target dataset distinctive feature point indices. | |
const PointCloudSource * | tmp_src_ |
Temporary pointer to the source dataset. | |
const PointCloudTarget * | tmp_tgt_ |
Temporary pointer to the target dataset. | |
const std::vector< float > * | tmp_weights_ |
Temporary pointer to weights of common point pairs. | |
boost::shared_ptr < pcl::WarpPointRigid < PointSource, PointTarget > > | warp_point_ |
The parameterized function used to warp the source to the target. | |
std::vector< double > | weights_ |
The vector of residual weights. Used internally in the LM loop. | |
Private Types | |
typedef pcl::PointCloud < PointSource > | PointCloudSource |
typedef PointCloudSource::ConstPtr | PointCloudSourceConstPtr |
typedef PointCloudSource::Ptr | PointCloudSourcePtr |
typedef pcl::PointCloud < PointTarget > | PointCloudTarget |
typedef pcl::PointIndices::ConstPtr | PointIndicesConstPtr |
typedef pcl::PointIndices::Ptr | PointIndicesPtr |
Private Member Functions | |
void | estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Eigen::Matrix4f &transformation_matrix) |
Estimate a rigid rotation transformation between a source and a target point cloud using LM. | |
void | estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const pcl::PointCloud< PointTarget > &cloud_tgt, const pcl::Correspondences &correspondences, Eigen::Matrix4f &transformation_matrix) |
Estimate a rigid rotation transformation between a source and a target point cloud using LM. | |
void | estimateRigidTransformation (const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &indices_src, const pcl::PointCloud< PointTarget > &cloud_tgt, Eigen::Matrix4f &transformation_matrix) |
Estimate a rigid rotation transformation between a source and a target point cloud using LM. | |
Private Attributes | |
float | alpha_ |
float | beta_ |
std::vector< int > | indices_src_dfp_ |
the vector of indices describing distinctive feature points in source cloud | |
bool | indices_src_dfp_set_ |
flag indicating if indices_src_dfp_ is set | |
std::vector< int > | indices_tgt_dfp_ |
the vector of indices describing distinctive feature points in target cloud | |
bool | indices_tgt_dfp_set_ |
flag indicating if indices_tgt_dfp_ is set | |
std::vector< float > | weights_dfp_ |
the vector containing weights of distinctive feature points correspondences | |
bool | weights_dfp_set_ |
flag indicating if vector containing weights of distinctive feature points correspondences is set | |
Friends | |
class | pcl::IterativeClosestPoint< PointSource, PointTarget > |
Definition at line 23 of file transformation_estimation_wdf.h.
typedef pcl::PointCloud<PointSource> TransformationEstimationWDF< PointSource, PointTarget >::PointCloudSource [private] |
Definition at line 24 of file transformation_estimation_wdf.h.
typedef PointCloudSource::ConstPtr TransformationEstimationWDF< PointSource, PointTarget >::PointCloudSourceConstPtr [private] |
Definition at line 26 of file transformation_estimation_wdf.h.
typedef PointCloudSource::Ptr TransformationEstimationWDF< PointSource, PointTarget >::PointCloudSourcePtr [private] |
Definition at line 25 of file transformation_estimation_wdf.h.
typedef pcl::PointCloud<PointTarget> TransformationEstimationWDF< PointSource, PointTarget >::PointCloudTarget [private] |
Definition at line 28 of file transformation_estimation_wdf.h.
typedef pcl::PointIndices::ConstPtr TransformationEstimationWDF< PointSource, PointTarget >::PointIndicesConstPtr [private] |
Definition at line 31 of file transformation_estimation_wdf.h.
typedef pcl::PointIndices::Ptr TransformationEstimationWDF< PointSource, PointTarget >::PointIndicesPtr [private] |
Definition at line 30 of file transformation_estimation_wdf.h.
TransformationEstimationWDF< PointSource, PointTarget >::TransformationEstimationWDF | ( | ) | [inline] |
Definition at line 80 of file transformation_estimation_wdf.h.
virtual TransformationEstimationWDF< PointSource, PointTarget >::~TransformationEstimationWDF | ( | ) | [inline, virtual] |
Definition at line 88 of file transformation_estimation_wdf.h.
virtual double TransformationEstimationWDF< PointSource, PointTarget >::computeDistance | ( | const PointSource & | p_src, |
const PointTarget & | p_tgt | ||
) | [inline, protected, virtual] |
Compute the distance between a source point and its corresponding target point.
p_src | The source point |
p_tgt | The target point |
Definition at line 208 of file transformation_estimation_wdf.h.
virtual double TransformationEstimationWDF< PointSource, PointTarget >::computeDistancePointToPlane | ( | const PointSource & | p_src, |
const PointTarget & | p_tgt | ||
) | [inline, protected, virtual] |
Definition at line 216 of file transformation_estimation_wdf.h.
virtual double TransformationEstimationWDF< PointSource, PointTarget >::computeDistanceWeight | ( | const double & | depth | ) | [inline, protected, virtual] |
Definition at line 226 of file transformation_estimation_wdf.h.
void TransformationEstimationWDF< PointSource, PointTarget >::estimateRigidTransformation | ( | const pcl::PointCloud< PointSource > & | cloud_src, |
const pcl::PointCloud< PointTarget > & | cloud_tgt, | ||
Eigen::Matrix4f & | transformation_matrix | ||
) | [inline, private, virtual] |
Estimate a rigid rotation transformation between a source and a target point cloud using LM.
[in] | cloud_src | the source point cloud dataset |
[in] | cloud_tgt | the target point cloud dataset |
[out] | transformation_matrix | the resultant transformation matrix |
Implements pcl::registration::TransformationEstimation< PointSource, PointTarget >.
Definition at line 87 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::estimateRigidTransformation | ( | const pcl::PointCloud< PointSource > & | cloud_src, |
const pcl::PointCloud< PointTarget > & | cloud_tgt, | ||
const pcl::Correspondences & | correspondences, | ||
Eigen::Matrix4f & | transformation_matrix | ||
) | [inline, private, virtual] |
Estimate a rigid rotation transformation between a source and a target point cloud using LM.
[in] | cloud_src | the source point cloud dataset |
[in] | cloud_tgt | the target point cloud dataset |
[in] | correspondences | the vector of correspondences between source and target point cloud |
[out] | transformation_matrix | the resultant transformation matrix |
Implements pcl::registration::TransformationEstimation< PointSource, PointTarget >.
Definition at line 95 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::estimateRigidTransformation | ( | const pcl::PointCloud< PointSource > & | cloud_src, |
const std::vector< int > & | indices_src, | ||
const pcl::PointCloud< PointTarget > & | cloud_tgt, | ||
Eigen::Matrix4f & | transformation_matrix | ||
) | [inline, private, virtual] |
Estimate a rigid rotation transformation between a source and a target point cloud using LM.
[in] | cloud_src | the source point cloud dataset |
[in] | indices_src | the vector of indices describing the points of interest in cloud_src |
[in] | cloud_tgt | the target point cloud dataset |
[out] | transformation_matrix | the resultant transformation matrix |
Implements pcl::registration::TransformationEstimation< PointSource, PointTarget >.
Definition at line 104 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::estimateRigidTransformation | ( | const pcl::PointCloud< PointSource > & | cloud_src, |
const std::vector< int > & | indices_src, | ||
const std::vector< int > & | indices_src_dfp, | ||
const pcl::PointCloud< PointTarget > & | cloud_tgt, | ||
const std::vector< int > & | indices_tgt, | ||
const std::vector< int > & | indices_tgt_dfp, | ||
float | alpha_arg, | ||
Eigen::Matrix4f & | transformation_matrix | ||
) | [inline] |
Estimate a rigid rotation transformation between a source and a target point cloud using WDF.
[in] | cloud_src | the source point cloud dataset |
[in] | indices_src | the vector of indices describing the points of interest in cloud_src |
[in] | indices_src_dfp | the vector of indices describing distinctive feature points in cloud_src |
[in] | cloud_tgt | the target point cloud dataset |
[in] | indices_tgt | the vector of indices describing the correspondences of the interest points from indices_src |
[in] | indices_tgt_dfp | the vector of indices describing correspondences of distinctive feature points from indices_src_dfp in cloud_tgt |
[in] | alpha | weight given to distinct features term in optimization equation (range [0,1]) |
[out] | transformation_matrix | the resultant transformation matrix |
Definition at line 114 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::estimateRigidTransformation | ( | const pcl::PointCloud< PointSource > & | cloud_src, |
const pcl::PointCloud< PointTarget > & | cloud_tgt, | ||
const pcl::Correspondences & | correspondences, | ||
const pcl::Correspondences & | correspondences_dfp, | ||
float | alpha_arg, | ||
Eigen::Matrix4f & | transformation_matrix | ||
) | [inline] |
Estimate a rigid rotation transformation between a source and a target point cloud using WDF.
[in] | cloud_src | the source point cloud dataset |
[in] | cloud_tgt | the target point cloud dataset |
[in] | correspondences | the vector of correspondences between source and target point cloud |
[in] | correspondences_dfp | the vector of distinctive feature point correspondences between source and target point cloud |
[in] | alpha | weight given to distinct features term in optimization equation (range [0,1]) |
[out] | transformation_matrix | the resultant transformation matrix |
Definition at line 305 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::estimateRigidTransformation | ( | const pcl::PointCloud< PointSource > & | cloud_src, |
const std::vector< int > & | indices_src, | ||
const pcl::PointCloud< PointTarget > & | cloud_tgt, | ||
const std::vector< int > & | indices_tgt, | ||
Eigen::Matrix4f & | transformation_matrix | ||
) | [inline, virtual] |
Estimate a rigid rotation transformation between a source and a target point cloud using WDF. This method has to be used in conjunction with methods setCorrespondecesDFP and setAlpha. In this manner it can be combined with pcl::IterativeClosestPoint via setTransformationEstimation method.
[in] | cloud_src | the source point cloud dataset |
[in] | indices_src | the vector of indices describing the points of interest in cloud_src |
[in] | cloud_tgt | the target point cloud dataset |
[in] | indices_tgt | the vector of indices describing the correspondences of the interst points from indices_src |
[out] | transformation_matrix | the resultant transformation matrix |
Implements pcl::registration::TransformationEstimation< PointSource, PointTarget >.
Definition at line 192 of file transformation_estimation_wdf.hpp.
float TransformationEstimationWDF< PointSource, PointTarget >::getAlpha | ( | void | ) | [inline] |
Definition at line 36 of file transformation_estimation_wdf.hpp.
float TransformationEstimationWDF< PointSource, PointTarget >::getBeta | ( | void | ) | [inline] |
Definition at line 46 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::setAlpha | ( | float | alpha_arg | ) | [inline] |
Definition at line 28 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::setBeta | ( | float | alpha_arg | ) | [inline] |
Definition at line 41 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::setCorrespondecesDFP | ( | pcl::Correspondences | correspondences_dfp | ) | [inline] |
Set correspondences between source and target cloud distinctive feature points. This has to be set when using this class with pcl::IterativeClosestPoint.
[in] | correspondences_dfp | the vector of distinctive feature point correspondences between source and target point cloud. Source cloud point is stored in pcl::Correspondence::index_query, and corresponding target cloud point in pcl::Correspondence::index_match. |
Definition at line 52 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::setCorrespondecesDFP | ( | std::vector< int > & | indices_src_dfp_arg, |
std::vector< int > & | indices_tgt_dfp_arg | ||
) | [inline] |
Set correspondences between source and target cloud distinctive feature points. This has to be set when using this class with pcl::IterativeClosestPoint.
[in] | indices_src_dfp_arg | the vector of indices describing the distinctive feature points in cloud source |
[in] | indices_tgt_dfp_arg | the vector of indices describing the correspondences of distinctive feature points indices_src_dfp_arg in cloud target |
Definition at line 68 of file transformation_estimation_wdf.hpp.
void TransformationEstimationWDF< PointSource, PointTarget >::setWarpFunction | ( | const boost::shared_ptr< pcl::WarpPointRigid< PointSource, PointTarget > > & | warp_fcn | ) | [inline] |
Set the function we use to warp points. Defaults to rigid 6D warp.
[in] | shared | pointer to object that warps points |
Definition at line 190 of file transformation_estimation_wdf.h.
void TransformationEstimationWDF< PointSource, PointTarget >::setWeightsDFP | ( | std::vector< float > | weights_dfp_arg | ) | [inline] |
Definition at line 80 of file transformation_estimation_wdf.hpp.
friend class pcl::IterativeClosestPoint< PointSource, PointTarget > [friend] |
Definition at line 197 of file transformation_estimation_wdf.h.
float TransformationEstimationWDF< PointSource, PointTarget >::alpha_ [private] |
Definition at line 33 of file transformation_estimation_wdf.h.
float TransformationEstimationWDF< PointSource, PointTarget >::beta_ [private] |
Definition at line 34 of file transformation_estimation_wdf.h.
std::vector<int> TransformationEstimationWDF< PointSource, PointTarget >::indices_src_dfp_ [private] |
the vector of indices describing distinctive feature points in source cloud
Definition at line 35 of file transformation_estimation_wdf.h.
bool TransformationEstimationWDF< PointSource, PointTarget >::indices_src_dfp_set_ [private] |
flag indicating if indices_src_dfp_ is set
Definition at line 37 of file transformation_estimation_wdf.h.
std::vector<int> TransformationEstimationWDF< PointSource, PointTarget >::indices_tgt_dfp_ [private] |
the vector of indices describing distinctive feature points in target cloud
Definition at line 36 of file transformation_estimation_wdf.h.
bool TransformationEstimationWDF< PointSource, PointTarget >::indices_tgt_dfp_set_ [private] |
flag indicating if indices_tgt_dfp_ is set
Definition at line 38 of file transformation_estimation_wdf.h.
const std::vector<float>* TransformationEstimationWDF< PointSource, PointTarget >::tmp_dfp_weights_ [protected] |
Temporary pointer to weights of distinctive feature point pairs.
Definition at line 259 of file transformation_estimation_wdf.h.
const std::vector<int>* TransformationEstimationWDF< PointSource, PointTarget >::tmp_idx_src_ [protected] |
Temporary pointer to the source dataset indices.
Definition at line 244 of file transformation_estimation_wdf.h.
const std::vector<int>* TransformationEstimationWDF< PointSource, PointTarget >::tmp_idx_src_dfp_ [protected] |
Temporary pointer to the source dataset distinctive feature point indices.
Definition at line 250 of file transformation_estimation_wdf.h.
const std::vector<int>* TransformationEstimationWDF< PointSource, PointTarget >::tmp_idx_tgt_ [protected] |
Temporary pointer to the target dataset indices.
Definition at line 247 of file transformation_estimation_wdf.h.
const std::vector<int>* TransformationEstimationWDF< PointSource, PointTarget >::tmp_idx_tgt_dfp_ [protected] |
Temporary pointer to the target dataset distinctive feature point indices.
Definition at line 253 of file transformation_estimation_wdf.h.
const PointCloudSource* TransformationEstimationWDF< PointSource, PointTarget >::tmp_src_ [protected] |
Temporary pointer to the source dataset.
Definition at line 238 of file transformation_estimation_wdf.h.
const PointCloudTarget* TransformationEstimationWDF< PointSource, PointTarget >::tmp_tgt_ [protected] |
Temporary pointer to the target dataset.
Definition at line 241 of file transformation_estimation_wdf.h.
const std::vector<float>* TransformationEstimationWDF< PointSource, PointTarget >::tmp_weights_ [protected] |
Temporary pointer to weights of common point pairs.
Definition at line 256 of file transformation_estimation_wdf.h.
boost::shared_ptr<pcl::WarpPointRigid<PointSource, PointTarget> > TransformationEstimationWDF< PointSource, PointTarget >::warp_point_ [protected] |
The parameterized function used to warp the source to the target.
Definition at line 262 of file transformation_estimation_wdf.h.
std::vector<double> TransformationEstimationWDF< PointSource, PointTarget >::weights_ [protected] |
The vector of residual weights. Used internally in the LM loop.
Definition at line 235 of file transformation_estimation_wdf.h.
std::vector<float> TransformationEstimationWDF< PointSource, PointTarget >::weights_dfp_ [private] |
the vector containing weights of distinctive feature points correspondences
Definition at line 39 of file transformation_estimation_wdf.h.
bool TransformationEstimationWDF< PointSource, PointTarget >::weights_dfp_set_ [private] |
flag indicating if vector containing weights of distinctive feature points correspondences is set
Definition at line 40 of file transformation_estimation_wdf.h.