Perform a fine alignment from source to target cloud with Generalized Iterative Closest Point.
More...
#include <GICPAlignment.h>
Perform a fine alignment from source to target cloud with Generalized Iterative Closest Point.
POINTCLOUDS:
- target pointcloud: should be obtained from converting a part's CAD. Use CADToPointCloud.
- source pointcloud: obtained from Leica scan and previously aligned with target using InitialAlignment.
Definition at line 32 of file GICPAlignment.h.
◆ CovariancesVector
◆ PointCloudNormal
◆ PointCloudRGB
◆ PointCloudXYZ
◆ GICPAlignment()
| GICPAlignment::GICPAlignment |
( |
PointCloudRGB::Ptr |
target_cloud, |
|
|
PointCloudRGB::Ptr |
source_cloud, |
|
|
bool |
use_covariances |
|
) |
| |
◆ ~GICPAlignment()
| GICPAlignment::~GICPAlignment |
( |
| ) |
|
|
inline |
◆ applyCovariances()
| void GICPAlignment::applyCovariances |
( |
| ) |
|
|
private |
◆ applyTFtoCloud()
| void GICPAlignment::applyTFtoCloud |
( |
PointCloudRGB::Ptr |
cloud | ) |
|
Once GICP is finished, apply fine transformation to source cloud.
- Parameters
-
Definition at line 144 of file GICPAlignment.cpp.
◆ backUp()
| void GICPAlignment::backUp |
( |
PointCloudRGB::Ptr |
cloud | ) |
|
|
private |
◆ configParameters()
| void GICPAlignment::configParameters |
( |
| ) |
|
|
private |
◆ fineAlignment()
| void GICPAlignment::fineAlignment |
( |
| ) |
|
|
private |
Apply GICP to perform fine alignment.
- Parameters
-
| [in] | source_cloud | |
| [in] | target_cloud | |
Definition at line 86 of file GICPAlignment.cpp.
◆ getAlignedCloud()
| void GICPAlignment::getAlignedCloud |
( |
PointCloudRGB::Ptr |
aligned_cloud | ) |
|
◆ getAlignedCloudROSMsg()
| void GICPAlignment::getAlignedCloudROSMsg |
( |
sensor_msgs::PointCloud2 & |
aligned_cloud_msg | ) |
|
Get the aligned cloud msg in PointCloud2 format.
- Parameters
-
Definition at line 161 of file GICPAlignment.cpp.
◆ getCovariances()
◆ getFineTransform()
| Eigen::Matrix4f GICPAlignment::getFineTransform |
( |
| ) |
|
Get the fine transform object.
- Returns
- Eigen::Matrix4f
Definition at line 149 of file GICPAlignment.cpp.
◆ iterate()
| void GICPAlignment::iterate |
( |
| ) |
|
◆ iterateFineAlignment()
| void GICPAlignment::iterateFineAlignment |
( |
PointCloudRGB::Ptr |
cloud | ) |
|
|
private |
Re-iterate GICP and save new aligned cloud.
- Parameters
-
Definition at line 111 of file GICPAlignment.cpp.
◆ run()
| void GICPAlignment::run |
( |
| ) |
|
◆ setMaxCorrespondenceDistance()
| void GICPAlignment::setMaxCorrespondenceDistance |
( |
int |
max_corresp_distance | ) |
|
Set the Max Correspondence Distance object.
- Parameters
-
Definition at line 188 of file GICPAlignment.cpp.
◆ setMaxIterations()
| void GICPAlignment::setMaxIterations |
( |
int |
iterations | ) |
|
◆ setRANSACOutlierTh()
| void GICPAlignment::setRANSACOutlierTh |
( |
int |
ransac_threshold | ) |
|
◆ setSourceCloud()
| void GICPAlignment::setSourceCloud |
( |
PointCloudRGB::Ptr |
source_cloud | ) |
|
◆ setTargetCloud()
| void GICPAlignment::setTargetCloud |
( |
PointCloudRGB::Ptr |
target_cloud | ) |
|
◆ setTfEpsilon()
| void GICPAlignment::setTfEpsilon |
( |
double |
tf_epsilon | ) |
|
◆ undo()
| void GICPAlignment::undo |
( |
| ) |
|
◆ aligned_cloud_
| PointCloudRGB::Ptr GICPAlignment::aligned_cloud_ |
|
private |
Source pointcloud aligned with target cloud.
Definition at line 178 of file GICPAlignment.h.
◆ backup_cloud_
| PointCloudRGB::Ptr GICPAlignment::backup_cloud_ |
|
private |
Save aligned pointcloud to restore if undo.
Definition at line 181 of file GICPAlignment.h.
◆ covariances_
| bool GICPAlignment::covariances_ |
|
private |
◆ fine_tf_
| Eigen::Matrix4f GICPAlignment::fine_tf_ |
|
private |
Transformation matrix as result of GICP alignment.
Definition at line 156 of file GICPAlignment.h.
◆ gicp_
| pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB> GICPAlignment::gicp_ |
|
private |
◆ max_corresp_distance_
| double GICPAlignment::max_corresp_distance_ |
|
private |
Value for Max CorrespondenceDistance for GICP.
Definition at line 166 of file GICPAlignment.h.
◆ max_iter_
| int GICPAlignment::max_iter_ |
|
private |
◆ ransac_outlier_th_
| double GICPAlignment::ransac_outlier_th_ |
|
private |
◆ source_cloud_
| PointCloudRGB::Ptr GICPAlignment::source_cloud_ |
|
private |
◆ target_cloud_
| PointCloudRGB::Ptr GICPAlignment::target_cloud_ |
|
private |
◆ tf_epsilon_
| double GICPAlignment::tf_epsilon_ |
|
private |
Value for TFEpsilon for GICP. Define the convergence criterion.
Definition at line 163 of file GICPAlignment.h.
◆ transform_exists_
| bool GICPAlignment::transform_exists_ |
If true, fine transformation is finished.
Definition at line 53 of file GICPAlignment.h.
The documentation for this class was generated from the following files: