GICPAlignment.h
Go to the documentation of this file.
1 
18 #pragma once
19 #ifndef _GICP_ALIGNMENT_H
20 #define _GICP_ALIGNMENT_H
21 
22 #include <Utils.h>
23 #include <pcl/registration/gicp.h>
24 
33 {
34  typedef pcl::PointCloud<pcl::PointXYZ> PointCloudXYZ;
35  typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloudRGB;
36  typedef pcl::PointCloud<pcl::Normal> PointCloudNormal;
37  typedef std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d>> CovariancesVector;
38 
39 public:
47  GICPAlignment(PointCloudRGB::Ptr target_cloud, PointCloudRGB::Ptr source_cloud, bool use_covariances);
48 
54 
56  bool transform_exists_;
57 
58 
63  void run();
64 
69  void iterate();
70 
75  void undo();
76 
82  Eigen::Matrix4f getFineTransform();
83 
89  void getAlignedCloud(PointCloudRGB::Ptr aligned_cloud);
90 
96  void getAlignedCloudROSMsg(sensor_msgs::PointCloud2& aligned_cloud_msg);
97 
103  void applyTFtoCloud(PointCloudRGB::Ptr cloud);
104 
110  void setSourceCloud(PointCloudRGB::Ptr source_cloud);
111 
117  void setTargetCloud(PointCloudRGB::Ptr target_cloud);
118 
124  void setMaxIterations(int iterations);
125 
131  void setTfEpsilon(double tf_epsilon);
132 
138  void setMaxCorrespondenceDistance(int max_corresp_distance);
139 
145  void setRANSACOutlierTh(int ransac_threshold);
146 
147 private:
148 
151 
153  pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB> gicp_;
154 
156  Eigen::Matrix4f fine_tf_;
157 
158 
161 
163  double tf_epsilon_;
164 
167 
170 
172  PointCloudRGB::Ptr target_cloud_;
173 
175  PointCloudRGB::Ptr source_cloud_;
176 
178  PointCloudRGB::Ptr aligned_cloud_;
179 
181  PointCloudRGB::Ptr backup_cloud_;
182 
187  void configParameters();
188 
195  void fineAlignment();
196 
203  void getCovariances(PointCloudRGB::Ptr cloud, boost::shared_ptr<CovariancesVector> covs);
204 
209  void applyCovariances();
210 
216  void iterateFineAlignment(PointCloudRGB::Ptr cloud);
217 
223  void backUp(PointCloudRGB::Ptr cloud);
224 };
225 
226 #endif
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
Definition: GICPAlignment.h:37
PointCloudRGB::Ptr backup_cloud_
Save aligned pointcloud to restore if undo.
void run()
Perform GICP alignment.
pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
Definition: GICPAlignment.h:34
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...
Definition: GICPAlignment.h:32
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
Definition: GICPAlignment.h:36
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.
Definition: GICPAlignment.h:53
~GICPAlignment()
Destroy the GICPAlignment object.
Definition: GICPAlignment.h:53
pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
Definition: GICPAlignment.h:35
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.


leica_point_cloud_processing
Author(s): Ines Lara Sicilia
autogenerated on Mon Feb 28 2022 22:40:47