Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
GICPAlignment Class Reference

Perform a fine alignment from source to target cloud with Generalized Iterative Closest Point. More...

#include <GICPAlignment.h>

Public Member Functions

void applyTFtoCloud (PointCloudRGB::Ptr cloud)
 Once GICP is finished, apply fine transformation to source cloud. More...
 
void getAlignedCloud (PointCloudRGB::Ptr aligned_cloud)
 Get the aligned cloud object. More...
 
void getAlignedCloudROSMsg (sensor_msgs::PointCloud2 &aligned_cloud_msg)
 Get the aligned cloud msg in PointCloud2 format. More...
 
Eigen::Matrix4f getFineTransform ()
 Get the fine transform object. More...
 
 GICPAlignment (PointCloudRGB::Ptr target_cloud, PointCloudRGB::Ptr source_cloud, bool use_covariances)
 Construct a new GICPAlignment object. More...
 
void iterate ()
 Do more iterations of GICP alignment. More...
 
void run ()
 Perform GICP alignment. More...
 
void setMaxCorrespondenceDistance (int max_corresp_distance)
 Set the Max Correspondence Distance object. More...
 
void setMaxIterations (int iterations)
 Set the Max Iterations object. More...
 
void setRANSACOutlierTh (int ransac_threshold)
 Set the RANSAC Outlier threshold. More...
 
void setSourceCloud (PointCloudRGB::Ptr source_cloud)
 Set the Source Cloud object. More...
 
void setTargetCloud (PointCloudRGB::Ptr target_cloud)
 Set the Target Cloud object. More...
 
void setTfEpsilon (double tf_epsilon)
 Set the Tf Epsilon object. More...
 
void undo ()
 Undo last iteration and back up results. More...
 
 ~GICPAlignment ()
 Destroy the GICPAlignment object. More...
 

Public Attributes

bool transform_exists_
 If true, fine transformation is finished. More...
 

Private Types

typedef std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > CovariancesVector
 
typedef pcl::PointCloud< pcl::Normal > PointCloudNormal
 
typedef pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
 

Private Member Functions

void applyCovariances ()
 Apply the covariances before running GICP. More...
 
void backUp (PointCloudRGB::Ptr cloud)
 Store cloud as backup cloud. More...
 
void configParameters ()
 Set parameters to compute GICP alignment. More...
 
void fineAlignment ()
 Apply GICP to perform fine alignment. More...
 
void getCovariances (PointCloudRGB::Ptr cloud, boost::shared_ptr< CovariancesVector > covs)
 Get the covariances from cloud. More...
 
void iterateFineAlignment (PointCloudRGB::Ptr cloud)
 Re-iterate GICP and save new aligned cloud. More...
 

Private Attributes

PointCloudRGB::Ptr aligned_cloud_
 Source pointcloud aligned with target cloud. More...
 
PointCloudRGB::Ptr backup_cloud_
 Save aligned pointcloud to restore if undo. More...
 
bool covariances_
 If true, perform GICP with convariances. More...
 
Eigen::Matrix4f fine_tf_
 Transformation matrix as result of GICP alignment. More...
 
pcl::GeneralizedIterativeClosestPoint< pcl::PointXYZRGB, pcl::PointXYZRGB > gicp_
 GICP object. More...
 
double max_corresp_distance_
 Value for Max CorrespondenceDistance for GICP. More...
 
int max_iter_
 Maximum number of GICP iterations. More...
 
double ransac_outlier_th_
 Value for RANSAC outlier threshold. More...
 
PointCloudRGB::Ptr source_cloud_
 Source pointcloud. More...
 
PointCloudRGB::Ptr target_cloud_
 Target pointcloud. More...
 
double tf_epsilon_
 Value for TFEpsilon for GICP. Define the convergence criterion. More...
 

Detailed Description

Perform a fine alignment from source to target cloud with Generalized Iterative Closest Point.

POINTCLOUDS:

Definition at line 32 of file GICPAlignment.h.

Member Typedef Documentation

typedef std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d> > GICPAlignment::CovariancesVector
private

Definition at line 37 of file GICPAlignment.h.

typedef pcl::PointCloud<pcl::Normal> GICPAlignment::PointCloudNormal
private

Definition at line 36 of file GICPAlignment.h.

typedef pcl::PointCloud<pcl::PointXYZRGB> GICPAlignment::PointCloudRGB
private

Definition at line 35 of file GICPAlignment.h.

typedef pcl::PointCloud<pcl::PointXYZ> GICPAlignment::PointCloudXYZ
private

Definition at line 34 of file GICPAlignment.h.

Constructor & Destructor Documentation

GICPAlignment::GICPAlignment ( PointCloudRGB::Ptr  target_cloud,
PointCloudRGB::Ptr  source_cloud,
bool  use_covariances 
)

Construct a new GICPAlignment object.

Parameters
[in]target_cloud
[in]source_cloud
[in]use_covariances

Definition at line 23 of file GICPAlignment.cpp.

GICPAlignment::~GICPAlignment ( )
inline

Destroy the GICPAlignment object.

Definition at line 53 of file GICPAlignment.h.

Member Function Documentation

void GICPAlignment::applyCovariances ( )
private

Apply the covariances before running GICP.

Definition at line 73 of file GICPAlignment.cpp.

void GICPAlignment::applyTFtoCloud ( PointCloudRGB::Ptr  cloud)

Once GICP is finished, apply fine transformation to source cloud.

Parameters
[out]cloud

Definition at line 144 of file GICPAlignment.cpp.

void GICPAlignment::backUp ( PointCloudRGB::Ptr  cloud)
private

Store cloud as backup cloud.

Parameters
[in]cloud

Definition at line 134 of file GICPAlignment.cpp.

void GICPAlignment::configParameters ( )
private

Set parameters to compute GICP alignment.

Definition at line 48 of file GICPAlignment.cpp.

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.

void GICPAlignment::getAlignedCloud ( PointCloudRGB::Ptr  aligned_cloud)

Get the aligned cloud object.

Parameters
[out]aligned_cloud

Definition at line 156 of file GICPAlignment.cpp.

void GICPAlignment::getAlignedCloudROSMsg ( sensor_msgs::PointCloud2 &  aligned_cloud_msg)

Get the aligned cloud msg in PointCloud2 format.

Parameters
[out]aligned_cloud_msg

Definition at line 161 of file GICPAlignment.cpp.

void GICPAlignment::getCovariances ( PointCloudRGB::Ptr  cloud,
boost::shared_ptr< CovariancesVector covs 
)
private

Get the covariances from cloud.

Parameters
[in]cloud
[out]covs

Definition at line 56 of file GICPAlignment.cpp.

Eigen::Matrix4f GICPAlignment::getFineTransform ( )

Get the fine transform object.

Returns
Eigen::Matrix4f

Definition at line 149 of file GICPAlignment.cpp.

void GICPAlignment::iterate ( )

Do more iterations of GICP alignment.

Definition at line 129 of file GICPAlignment.cpp.

void GICPAlignment::iterateFineAlignment ( PointCloudRGB::Ptr  cloud)
private

Re-iterate GICP and save new aligned cloud.

Parameters
[out]cloud

Definition at line 111 of file GICPAlignment.cpp.

void GICPAlignment::run ( )

Perform GICP alignment.

Definition at line 37 of file GICPAlignment.cpp.

void GICPAlignment::setMaxCorrespondenceDistance ( int  max_corresp_distance)

Set the Max Correspondence Distance object.

Parameters
max_corresp_distance

Definition at line 188 of file GICPAlignment.cpp.

void GICPAlignment::setMaxIterations ( int  iterations)

Set the Max Iterations object.

Parameters
iterations

Definition at line 176 of file GICPAlignment.cpp.

void GICPAlignment::setRANSACOutlierTh ( int  ransac_threshold)

Set the RANSAC Outlier threshold.

Parameters
ransac_threshold

Definition at line 194 of file GICPAlignment.cpp.

void GICPAlignment::setSourceCloud ( PointCloudRGB::Ptr  source_cloud)

Set the Source Cloud object.

Parameters
source_cloud

Definition at line 166 of file GICPAlignment.cpp.

void GICPAlignment::setTargetCloud ( PointCloudRGB::Ptr  target_cloud)

Set the Target Cloud object.

Parameters
target_cloud

Definition at line 171 of file GICPAlignment.cpp.

void GICPAlignment::setTfEpsilon ( double  tf_epsilon)

Set the Tf Epsilon object.

Parameters
tf_epsilon

Definition at line 182 of file GICPAlignment.cpp.

void GICPAlignment::undo ( )

Undo last iteration and back up results.

Definition at line 139 of file GICPAlignment.cpp.

Member Data Documentation

PointCloudRGB::Ptr GICPAlignment::aligned_cloud_
private

Source pointcloud aligned with target cloud.

Definition at line 178 of file GICPAlignment.h.

PointCloudRGB::Ptr GICPAlignment::backup_cloud_
private

Save aligned pointcloud to restore if undo.

Definition at line 181 of file GICPAlignment.h.

bool GICPAlignment::covariances_
private

If true, perform GICP with convariances.

Definition at line 150 of file GICPAlignment.h.

Eigen::Matrix4f GICPAlignment::fine_tf_
private

Transformation matrix as result of GICP alignment.

Definition at line 156 of file GICPAlignment.h.

pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB> GICPAlignment::gicp_
private

GICP object.

Definition at line 153 of file GICPAlignment.h.

double GICPAlignment::max_corresp_distance_
private

Value for Max CorrespondenceDistance for GICP.

Definition at line 166 of file GICPAlignment.h.

int GICPAlignment::max_iter_
private

Maximum number of GICP iterations.

Definition at line 160 of file GICPAlignment.h.

double GICPAlignment::ransac_outlier_th_
private

Value for RANSAC outlier threshold.

Definition at line 169 of file GICPAlignment.h.

PointCloudRGB::Ptr GICPAlignment::source_cloud_
private

Source pointcloud.

Definition at line 175 of file GICPAlignment.h.

PointCloudRGB::Ptr GICPAlignment::target_cloud_
private

Target pointcloud.

Definition at line 172 of file GICPAlignment.h.

double GICPAlignment::tf_epsilon_
private

Value for TFEpsilon for GICP. Define the convergence criterion.

Definition at line 163 of file GICPAlignment.h.

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:


leica_point_cloud_processing
Author(s): Ines Lara Sicilia
autogenerated on Fri Feb 5 2021 03:20:30