19 #ifndef _GICP_ALIGNMENT_H    20 #define _GICP_ALIGNMENT_H    23 #include <pcl/registration/gicp.h>    37     typedef std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d>> 
CovariancesVector;
    47     GICPAlignment(PointCloudRGB::Ptr target_cloud, PointCloudRGB::Ptr source_cloud, 
bool use_covariances);
   153     pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB> 
gicp_;
   223     void backUp(PointCloudRGB::Ptr cloud);  
 double tf_epsilon_
Value for TFEpsilon for GICP. Define the convergence criterion. 
void undo()
Undo last iteration and back up results. 
void getCovariances(PointCloudRGB::Ptr cloud, boost::shared_ptr< CovariancesVector > covs)
Get the covariances from cloud. 
double ransac_outlier_th_
Value for RANSAC outlier threshold. 
std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > CovariancesVector
PointCloudRGB::Ptr backup_cloud_
Save aligned pointcloud to restore if undo. 
void run()
Perform GICP alignment. 
pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
bool covariances_
If true, perform GICP with convariances. 
void setTargetCloud(PointCloudRGB::Ptr target_cloud)
Set the Target Cloud object. 
void configParameters()
Set parameters to compute GICP alignment. 
Perform a fine alignment from source to target cloud with Generalized Iterative Closest Point...
void iterate()
Do more iterations of GICP alignment. 
void applyTFtoCloud(PointCloudRGB::Ptr cloud)
Once GICP is finished, apply fine transformation to source cloud. 
void setTfEpsilon(double tf_epsilon)
Set the Tf Epsilon object. 
pcl::PointCloud< pcl::Normal > PointCloudNormal
GICPAlignment(PointCloudRGB::Ptr target_cloud, PointCloudRGB::Ptr source_cloud, bool use_covariances)
Construct a new GICPAlignment object. 
void getAlignedCloud(PointCloudRGB::Ptr aligned_cloud)
Get the aligned cloud object. 
void setSourceCloud(PointCloudRGB::Ptr source_cloud)
Set the Source Cloud object. 
PointCloudRGB::Ptr source_cloud_
Source pointcloud. 
bool transform_exists_
If true, fine transformation is finished. 
~GICPAlignment()
Destroy the GICPAlignment object. 
pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
void setRANSACOutlierTh(int ransac_threshold)
Set the RANSAC Outlier threshold. 
void fineAlignment()
Apply GICP to perform fine alignment. 
double max_corresp_distance_
Value for Max CorrespondenceDistance for GICP. 
void setMaxCorrespondenceDistance(int max_corresp_distance)
Set the Max Correspondence Distance object. 
void iterateFineAlignment(PointCloudRGB::Ptr cloud)
Re-iterate GICP and save new aligned cloud. 
void setMaxIterations(int iterations)
Set the Max Iterations object. 
void applyCovariances()
Apply the covariances before running GICP. 
pcl::GeneralizedIterativeClosestPoint< pcl::PointXYZRGB, pcl::PointXYZRGB > gicp_
GICP object. 
void getAlignedCloudROSMsg(sensor_msgs::PointCloud2 &aligned_cloud_msg)
Get the aligned cloud msg in PointCloud2 format. 
PointCloudRGB::Ptr aligned_cloud_
Source pointcloud aligned with target cloud. 
Eigen::Matrix4f fine_tf_
Transformation matrix as result of GICP alignment. 
Eigen::Matrix4f getFineTransform()
Get the fine transform object. 
PointCloudRGB::Ptr target_cloud_
Target pointcloud. 
void backUp(PointCloudRGB::Ptr cloud)
Store cloud as backup cloud. 
int max_iter_
Maximum number of GICP iterations.