#include <InitialAlignment.h>
Public Member Functions | |
void | applyTFtoCloud (PointCloudRGB::Ptr cloud) |
Once initial alignment is finished, apply rigid transformation to given cloud. More... | |
void | applyTFtoCloud (PointCloudRGB::Ptr cloud, Eigen::Matrix4f tf) |
Apply given tf to 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 | getRigidTransform () |
Get the rigid transform object. More... | |
InitialAlignment (PointCloudRGB::Ptr target_cloud, PointCloudRGB::Ptr source_cloud) | |
Construct a new Initial Alignment object. More... | |
void | run () |
Perform initial alignment. More... | |
void | setMethod (AlignmentMethod method) |
Set the AlignmentMethod object. More... | |
void | setRadiusFactor (double align_factor) |
Set the Radius Factor object. More... | |
~InitialAlignment () | |
Destroy the Initial Alignment object. More... | |
Public Attributes | |
bool | transform_exists_ |
If true, rigid transformation is complete. More... | |
Private Types | |
typedef pcl::PointCloud< pcl::FPFHSignature33 > | PointCloudFPFH |
typedef pcl::PointCloud< pcl::Normal > | PointCloudNormal |
typedef pcl::PointCloud< pcl::PointXYZRGB > | PointCloudRGB |
typedef pcl::PointCloud< pcl::PointXYZ > | PointCloudXYZ |
Private Member Functions | |
void | applyTFtoCloud () |
Once initial alignment is finished, apply rigid transformation to source cloud. More... | |
void | estimateTransform () |
Get transform from computed correspondences. More... | |
bool | findIdx (Eigen::MatrixXd source_m, Eigen::MatrixXd target_m, Eigen::MatrixXi source_idx_m, Eigen::MatrixXi target_idx_m, std::vector< int > &source_indx, std::vector< int > &target_indx) |
Function to get index for Source matrix value in Target matrix. More... | |
Eigen::Matrix3f | getCoordinateSystem (PointCloudNormal::Ptr normals, std::vector< int > &index) |
Create coordinate system from corresponden normals. More... | |
void | getTransformationFromNormals (PointCloudNormal::Ptr source_normals, PointCloudNormal::Ptr target_normals) |
Get transformation between cloud based on normals correspondences. More... | |
void | matrixFromAngles (PointCloudNormal::Ptr normal, size_t size, Eigen::MatrixXd &matrix, Eigen::MatrixXi &index_matrix) |
Construct matrix based on angles between normals. More... | |
Eigen::VectorXd | nextVector (Eigen::MatrixXd matrix, int current_col, int current_row) |
Get next matrix vector with extracted current col and row. More... | |
bool | normalsCorrespondences (PointCloudNormal::Ptr source_dominant_normal, PointCloudNormal::Ptr target_dominant_normal, std::vector< int > &source_idx, std::vector< int > &target_idx) |
Found correspondences between dominant normals. More... | |
int | obtainBoundaryKeypoints (PointCloudRGB::Ptr cloud, PointCloudNormal::Ptr normals, PointCloudRGB::Ptr keypoints_cloud, pcl::IndicesPtr keypoints_indices, pcl::IndicesPtr non_keypoints_indices) |
Obtain cloud keypoints based on boundary method. More... | |
void | obtainCorrespondences () |
Get correspondences between clouds from computed features. More... | |
void | obtainDominantNormals (PointCloudNormal::Ptr normals, std::vector< pcl::PointIndices > cluster_indices, PointCloudNormal::Ptr dominant_normals) |
Obtain dominant normal in given cluster. More... | |
int | obtainFeatures (PointCloudRGB::Ptr cloud, PointCloudNormal::Ptr normals, pcl::IndicesPtr keypoints_indices, PointCloudFPFH::Ptr features) |
Obtain cloud features based on given keypoints. More... | |
int | obtainHarrisKeypoints (PointCloudRGB::Ptr cloud, PointCloudNormal::Ptr normals, PointCloudRGB::Ptr keypoints_cloud, pcl::IndicesPtr keypoints_indices) |
Obtain cloud keypoints based on harris method. More... | |
int | obtainKeypointsAndFeatures (PointCloudRGB::Ptr cloud, PointCloudNormal::Ptr normals, PointCloudRGB::Ptr keypoints_cloud, PointCloudFPFH::Ptr features_cloud) |
Obtain keypoints and features based on set method. More... | |
int | obtainMultiScaleKeypointsAndFeatures (PointCloudRGB::Ptr cloud, PointCloudNormal::Ptr normals, PointCloudRGB::Ptr keypoints_cloud, pcl::IndicesPtr keypoints_indices, PointCloudFPFH::Ptr features) |
Obtain cloud keypoints based on multiscale method. More... | |
void | obtainNormalsCluster (PointCloudRGB::Ptr cloud, PointCloudNormal::Ptr normals, std::vector< pcl::PointIndices > &cluster_indices) |
Cluster clouds normals. More... | |
void | rejectCorrespondences () |
Reject computed correspondences. More... | |
void | rejectOneToOneCorrespondences () |
Reject computed correspondences. More... | |
void | runKeypointsBasedAlgorithm () |
Run keypoints based algorithm. Compute keypoints and features, found correspondences and get transform. More... | |
void | runNormalsBasedAlgorithm () |
If set method is NORMALS run algorithm. Cluster normals and found correspondences between dominant normals. Get transform between clouds. More... | |
Private Attributes | |
PointCloudRGB::Ptr | aligned_cloud_ |
Source pointcloud aligned with target cloud. More... | |
pcl::CorrespondencesPtr | correspondences_ |
Correspondences between source and target. More... | |
AlignmentMethod | method_ |
The alignment method. More... | |
double | normal_radius_ |
Radius to compute normals. More... | |
double | radius_factor_ |
Factor to apply to radius for computations. More... | |
Eigen::Matrix4f | rigid_tf_ |
Transformation matrix as result of initial alignment. More... | |
Eigen::Vector4f | source_centroid_ |
Source centroid computed. More... | |
PointCloudRGB::Ptr | source_cloud_ |
Source pointcloud. More... | |
PointCloudNormal::Ptr | source_dominant_normals_ |
Source dominant normals. Just used int NORMALS method. More... | |
PointCloudFPFH::Ptr | source_features_ |
Source features. More... | |
PointCloudRGB::Ptr | source_keypoints_ |
Source keypoints. More... | |
PointCloudNormal::Ptr | source_normals_ |
Source normals. More... | |
Eigen::Vector4f | target_centroid_ |
Target centroid computed. More... | |
PointCloudRGB::Ptr | target_cloud_ |
Target pointcloud. More... | |
PointCloudNormal::Ptr | target_dominant_normals_ |
Target dominant normals. Just used int NORMALS method. More... | |
PointCloudFPFH::Ptr | target_features_ |
Target features. More... | |
PointCloudRGB::Ptr | target_keypoints_ |
Target keypoints. More... | |
PointCloudNormal::Ptr | target_normals_ |
Target normals. More... | |
Definition at line 60 of file InitialAlignment.h.
|
private |
Definition at line 65 of file InitialAlignment.h.
|
private |
Definition at line 64 of file InitialAlignment.h.
|
private |
Definition at line 63 of file InitialAlignment.h.
|
private |
Definition at line 62 of file InitialAlignment.h.
InitialAlignment::InitialAlignment | ( | PointCloudRGB::Ptr | target_cloud, |
PointCloudRGB::Ptr | source_cloud | ||
) |
Construct a new Initial Alignment object.
[in] | target_cloud | |
[in] | source_cloud |
Definition at line 32 of file InitialAlignment.cpp.
|
inline |
Destroy the Initial Alignment object.
Definition at line 80 of file InitialAlignment.h.
void InitialAlignment::applyTFtoCloud | ( | PointCloudRGB::Ptr | cloud | ) |
Once initial alignment is finished, apply rigid transformation to given cloud.
[out] | cloud |
Definition at line 552 of file InitialAlignment.cpp.
void InitialAlignment::applyTFtoCloud | ( | PointCloudRGB::Ptr | cloud, |
Eigen::Matrix4f | tf | ||
) |
Apply given tf to cloud.
[out] | cloud | |
[in] | tf |
Definition at line 557 of file InitialAlignment.cpp.
|
private |
Once initial alignment is finished, apply rigid transformation to source cloud.
Definition at line 547 of file InitialAlignment.cpp.
|
private |
Get transform from computed correspondences.
Definition at line 540 of file InitialAlignment.cpp.
|
private |
Function to get index for Source matrix value in Target matrix.
[in] | source_m | source matrix form by angle between normals |
[in] | target_m | target matrix form by angle between normals |
[in] | source_idx_m | source matrix form by index of source_m |
[in] | target_idx_m | target matrix form by index of target_m |
[out] | source_indx | source indexes that correspond with target indexes |
[out] | target_indx | source indexes that correspond with target indexes |
Definition at line 233 of file InitialAlignment.cpp.
void InitialAlignment::getAlignedCloud | ( | PointCloudRGB::Ptr | aligned_cloud | ) |
Get the aligned cloud object.
[out] | aligned_cloud |
Definition at line 562 of file InitialAlignment.cpp.
void InitialAlignment::getAlignedCloudROSMsg | ( | sensor_msgs::PointCloud2 & | aligned_cloud_msg | ) |
Get the aligned cloud msg in PointCloud2 format.
[out] | aligned_cloud_msg |
Definition at line 567 of file InitialAlignment.cpp.
|
private |
Create coordinate system from corresponden normals.
normals | |
index |
Definition at line 327 of file InitialAlignment.cpp.
Eigen::Matrix4f InitialAlignment::getRigidTransform | ( | ) |
Get the rigid transform object.
Definition at line 572 of file InitialAlignment.cpp.
|
private |
Get transformation between cloud based on normals correspondences.
[in] | source_normals | |
[in] | target_normals |
Definition at line 189 of file InitialAlignment.cpp.
|
private |
Construct matrix based on angles between normals.
[in] | normal | |
[in] | size | |
[out] | matrix | |
[out] | index_matrix |
Definition at line 345 of file InitialAlignment.cpp.
|
private |
Get next matrix vector with extracted current col and row.
matrix | |
current_col | |
current_row |
Definition at line 223 of file InitialAlignment.cpp.
|
private |
Found correspondences between dominant normals.
[in] | source_dominant_normal | |
[in] | target_dominant_normal | |
[out] | source_idx | |
[out] | target_idx |
Definition at line 289 of file InitialAlignment.cpp.
|
private |
Obtain cloud keypoints based on boundary method.
[in] | cloud | |
[in] | normals | |
[out] | keypoints_cloud | |
[out] | keypoints_indices | |
[out] | non_keypoints_indices |
Definition at line 426 of file InitialAlignment.cpp.
|
private |
Get correspondences between clouds from computed features.
Definition at line 510 of file InitialAlignment.cpp.
|
private |
Obtain dominant normal in given cluster.
[in] | normals | |
[in] | cluster_indices | |
[out] | dominant_normals |
Definition at line 163 of file InitialAlignment.cpp.
|
private |
Obtain cloud features based on given keypoints.
[in] | cloud | |
[in] | normals | |
[in] | keypoints_indices | |
[out] | features |
Definition at line 487 of file InitialAlignment.cpp.
|
private |
Obtain cloud keypoints based on harris method.
cloud | |
normals | |
keypoints_cloud | |
keypoints_indices |
Definition at line 399 of file InitialAlignment.cpp.
|
private |
Obtain keypoints and features based on set method.
cloud | |
normals | |
keypoints_cloud | |
features_cloud |
Definition at line 366 of file InitialAlignment.cpp.
|
private |
Obtain cloud keypoints based on multiscale method.
[in] | cloud | |
[in] | normals | |
[out] | keypoints_cloud | |
[out] | keypoints_indices | |
[out] | features |
Definition at line 458 of file InitialAlignment.cpp.
|
private |
Cluster clouds normals.
[in] | cloud | |
[in] | normals | |
[out] | cluster_indices |
Definition at line 130 of file InitialAlignment.cpp.
|
private |
Reject computed correspondences.
Definition at line 519 of file InitialAlignment.cpp.
|
private |
Reject computed correspondences.
Definition at line 532 of file InitialAlignment.cpp.
void InitialAlignment::run | ( | ) |
Perform initial alignment.
Definition at line 62 of file InitialAlignment.cpp.
|
private |
Run keypoints based algorithm. Compute keypoints and features, found correspondences and get transform.
Definition at line 117 of file InitialAlignment.cpp.
|
private |
If set method is NORMALS run algorithm. Cluster normals and found correspondences between dominant normals. Get transform between clouds.
Definition at line 81 of file InitialAlignment.cpp.
void InitialAlignment::setMethod | ( | AlignmentMethod | method | ) |
Set the AlignmentMethod object.
method |
Definition at line 577 of file InitialAlignment.cpp.
void InitialAlignment::setRadiusFactor | ( | double | align_factor | ) |
Set the Radius Factor object.
align_factor |
Definition at line 582 of file InitialAlignment.cpp.
|
private |
Source pointcloud aligned with target cloud.
Definition at line 158 of file InitialAlignment.h.
|
private |
Correspondences between source and target.
Definition at line 185 of file InitialAlignment.h.
|
private |
The alignment method.
Definition at line 188 of file InitialAlignment.h.
|
private |
Radius to compute normals.
Definition at line 146 of file InitialAlignment.h.
|
private |
Factor to apply to radius for computations.
Definition at line 149 of file InitialAlignment.h.
|
private |
Transformation matrix as result of initial alignment.
Definition at line 143 of file InitialAlignment.h.
|
private |
Source centroid computed.
Definition at line 191 of file InitialAlignment.h.
|
private |
Source pointcloud.
Definition at line 155 of file InitialAlignment.h.
|
private |
Source dominant normals. Just used int NORMALS method.
Definition at line 167 of file InitialAlignment.h.
|
private |
Source features.
Definition at line 182 of file InitialAlignment.h.
|
private |
Source keypoints.
Definition at line 176 of file InitialAlignment.h.
|
private |
Source normals.
Definition at line 161 of file InitialAlignment.h.
|
private |
Target centroid computed.
Definition at line 194 of file InitialAlignment.h.
|
private |
Target pointcloud.
Definition at line 152 of file InitialAlignment.h.
|
private |
Target dominant normals. Just used int NORMALS method.
Definition at line 170 of file InitialAlignment.h.
|
private |
Target features.
Definition at line 179 of file InitialAlignment.h.
|
private |
Target keypoints.
Definition at line 173 of file InitialAlignment.h.
|
private |
Target normals.
Definition at line 164 of file InitialAlignment.h.
bool InitialAlignment::transform_exists_ |
If true, rigid transformation is complete.
Definition at line 80 of file InitialAlignment.h.