|
|
FPCSInitialAlignment () |
|
Constructor. More...
|
|
|
~FPCSInitialAlignment () |
|
Destructor. More...
|
|
void |
setTargetIndices (const IndicesPtr &target_indices) |
|
Provide a pointer to the vector of target indices. More...
|
|
IndicesPtr |
getTargetIndices () const |
|
void |
setSourceNormals (const NormalsConstPtr &source_normals) |
|
Provide a pointer to the normals of the source point cloud. More...
|
|
NormalsConstPtr |
getSourceNormals () const |
|
void |
setTargetNormals (const NormalsConstPtr &target_normals) |
|
Provide a pointer to the normals of the target point cloud. More...
|
|
NormalsConstPtr |
getTargetNormals () const |
|
void |
setNumberOfThreads (int nr_threads) |
|
Set the number of used threads if OpenMP is activated. More...
|
|
int |
getNumberOfThreads () const |
|
void |
setDelta (float delta, bool normalize=false) |
|
Set the constant factor delta which weights the internally calculated parameters. More...
|
|
float |
getDelta () const |
|
void |
setApproxOverlap (float approx_overlap) |
|
Set the approximate overlap between source and target. More...
|
|
float |
getApproxOverlap () const |
|
void |
setScoreThreshold (float score_threshold) |
|
Set the scoring threshold used for early finishing the method. More...
|
|
float |
getScoreThreshold () const |
|
void |
setNumberOfSamples (int nr_samples) |
|
Set the number of source samples to use during alignment. More...
|
|
int |
getNumberOfSamples () const |
|
void |
setMaxNormalDifference (float max_norm_diff) |
|
Set the maximum normal difference between valid point correspondences in degree. More...
|
|
float |
getMaxNormalDifference () const |
|
void |
setMaxComputationTime (int max_runtime) |
|
Set the maximum computation time in seconds. More...
|
|
int |
getMaxComputationTime () const |
|
float |
getFitnessScore () const |
|
|
Registration () |
|
Empty constructor. More...
|
|
|
~Registration () |
|
destructor. More...
|
|
void |
setTransformationEstimation (const TransformationEstimationPtr &te) |
|
Provide a pointer to the transformation estimation object. More...
|
|
void |
setCorrespondenceEstimation (const CorrespondenceEstimationPtr &ce) |
|
Provide a pointer to the correspondence estimation object. More...
|
|
virtual void |
setInputSource (const PointCloudSourceConstPtr &cloud) |
|
Provide a pointer to the input source (e.g., the point cloud that we want to align to the target) More...
|
|
const PointCloudSourceConstPtr |
getInputSource () |
|
Get a pointer to the input point cloud dataset target. More...
|
|
virtual void |
setInputTarget (const PointCloudTargetConstPtr &cloud) |
|
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to) More...
|
|
const PointCloudTargetConstPtr |
getInputTarget () |
|
Get a pointer to the input point cloud dataset target. More...
|
|
void |
setSearchMethodTarget (const KdTreePtr &tree, bool force_no_recompute=false) |
|
Provide a pointer to the search object used to find correspondences in the target cloud. More...
|
|
KdTreePtr |
getSearchMethodTarget () const |
|
Get a pointer to the search method used to find correspondences in the target cloud. More...
|
|
void |
setSearchMethodSource (const KdTreeReciprocalPtr &tree, bool force_no_recompute=false) |
|
Provide a pointer to the search object used to find correspondences in the source cloud (usually used by reciprocal correspondence finding). More...
|
|
KdTreeReciprocalPtr |
getSearchMethodSource () const |
|
Get a pointer to the search method used to find correspondences in the source cloud. More...
|
|
Matrix4 |
getFinalTransformation () |
|
Get the final transformation matrix estimated by the registration method. More...
|
|
Matrix4 |
getLastIncrementalTransformation () |
|
Get the last incremental transformation matrix estimated by the registration method. More...
|
|
void |
setMaximumIterations (int nr_iterations) |
|
Set the maximum number of iterations the internal optimization should run for. More...
|
|
int |
getMaximumIterations () |
|
Get the maximum number of iterations the internal optimization should run for, as set by the user. More...
|
|
void |
setRANSACIterations (int ransac_iterations) |
|
Set the number of iterations RANSAC should run for. More...
|
|
double |
getRANSACIterations () |
|
Get the number of iterations RANSAC should run for, as set by the user. More...
|
|
void |
setRANSACOutlierRejectionThreshold (double inlier_threshold) |
|
Set the inlier distance threshold for the internal RANSAC outlier rejection loop. More...
|
|
double |
getRANSACOutlierRejectionThreshold () |
|
Get the inlier distance threshold for the internal outlier rejection loop as set by the user. More...
|
|
void |
setMaxCorrespondenceDistance (double distance_threshold) |
|
Set the maximum distance threshold between two correspondent points in source <-> target. More...
|
|
double |
getMaxCorrespondenceDistance () |
|
Get the maximum distance threshold between two correspondent points in source <-> target. More...
|
|
void |
setTransformationEpsilon (double epsilon) |
|
Set the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. More...
|
|
double |
getTransformationEpsilon () |
|
Get the transformation epsilon (maximum allowable translation squared difference between two consecutive transformations) as set by the user. More...
|
|
void |
setTransformationRotationEpsilon (double epsilon) |
|
Set the transformation rotation epsilon (maximum allowable rotation difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution. More...
|
|
double |
getTransformationRotationEpsilon () |
|
Get the transformation rotation epsilon (maximum allowable difference between two consecutive transformations) as set by the user (epsilon is the cos(angle) in a axis-angle representation). More...
|
|
void |
setEuclideanFitnessEpsilon (double epsilon) |
|
Set the maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged. More...
|
|
double |
getEuclideanFitnessEpsilon () |
|
Get the maximum allowed distance error before the algorithm will be considered to have converged, as set by the user. More...
|
|
void |
setPointRepresentation (const PointRepresentationConstPtr &point_representation) |
|
Provide a boost shared pointer to the PointRepresentation to be used when comparing points. More...
|
|
bool |
registerVisualizationCallback (std::function< UpdateVisualizerCallbackSignature > &visualizerCallback) |
|
Register the user callback function which will be called from registration thread in order to update point cloud obtained after each iteration. More...
|
|
double |
getFitnessScore (double max_range=std::numeric_limits< double >::max()) |
|
Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target) More...
|
|
double |
getFitnessScore (const std::vector< float > &distances_a, const std::vector< float > &distances_b) |
|
Obtain the Euclidean fitness score (e.g., mean of squared distances from the source to the target) from two sets of correspondence distances (distances between source and target points) More...
|
|
bool |
hasConverged () const |
|
Return the state of convergence after the last align run. More...
|
|
void |
align (PointCloudSource &output) |
|
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output. More...
|
|
void |
align (PointCloudSource &output, const Matrix4 &guess) |
|
Call the registration algorithm which estimates the transformation and returns the transformed source (input) as output. More...
|
|
const std::string & |
getClassName () const |
|
Abstract class get name method. More...
|
|
bool |
initCompute () |
|
Internal computation initialization. More...
|
|
bool |
initComputeReciprocal () |
|
Internal computation when reciprocal lookup is needed. More...
|
|
void |
addCorrespondenceRejector (const CorrespondenceRejectorPtr &rejector) |
|
Add a new correspondence rejector to the list. More...
|
|
std::vector< CorrespondenceRejectorPtr > |
getCorrespondenceRejectors () |
|
Get the list of correspondence rejectors. More...
|
|
bool |
removeCorrespondenceRejector (unsigned int i) |
|
Remove the i-th correspondence rejector in the list. More...
|
|
void |
clearCorrespondenceRejectors () |
|
Clear the list of correspondence rejectors. More...
|
|
|
PCLBase () |
|
Empty constructor. More...
|
|
|
PCLBase (const PCLBase &base) |
|
Copy constructor. More...
|
|
virtual |
~PCLBase ()=default |
|
Destructor. More...
|
|
virtual void |
setInputCloud (const PointCloudConstPtr &cloud) |
|
Provide a pointer to the input dataset. More...
|
|
const PointCloudConstPtr |
getInputCloud () const |
|
Get a pointer to the input point cloud dataset. More...
|
|
virtual void |
setIndices (const IndicesPtr &indices) |
|
Provide a pointer to the vector of indices that represents the input data. More...
|
|
virtual void |
setIndices (const IndicesConstPtr &indices) |
|
Provide a pointer to the vector of indices that represents the input data. More...
|
|
virtual void |
setIndices (const PointIndicesConstPtr &indices) |
|
Provide a pointer to the vector of indices that represents the input data. More...
|
|
virtual void |
setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols) |
|
Set the indices for the points laying within an interest region of the point cloud. More...
|
|
IndicesPtr |
getIndices () |
|
Get a pointer to the vector of indices used. More...
|
|
const IndicesConstPtr |
getIndices () const |
|
Get a pointer to the vector of indices used. More...
|
|
const PointSource & |
operator[] (std::size_t pos) const |
|
Override PointCloud operator[] to shorten code. More...
|
|
|
void |
computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess) override |
|
Rigid transformation computation method. More...
|
|
virtual bool |
initCompute () |
|
Internal computation initialization. More...
|
|
int |
selectBase (pcl::Indices &base_indices, float(&ratio)[2]) |
|
Select an approximately coplanar set of four points from the source cloud. More...
|
|
int |
selectBaseTriangle (pcl::Indices &base_indices) |
|
Select randomly a triplet of points with large point-to-point distances. More...
|
|
void |
setupBase (pcl::Indices &base_indices, float(&ratio)[2]) |
|
Setup the base (four coplanar points) by ordering the points and computing intersection ratios and segment to segment distances of base diagonal. More...
|
|
float |
segmentToSegmentDist (const pcl::Indices &base_indices, float(&ratio)[2]) |
|
Calculate intersection ratios and segment to segment distances of base diagonals. More...
|
|
virtual int |
bruteForceCorrespondences (int idx1, int idx2, pcl::Correspondences &pairs) |
|
Search for corresponding point pairs given the distance between two base points. More...
|
|
virtual int |
determineBaseMatches (const pcl::Indices &base_indices, std::vector< pcl::Indices > &matches, const pcl::Correspondences &pairs_a, const pcl::Correspondences &pairs_b, const float(&ratio)[2]) |
|
Determine base matches by combining the point pair candidate and search for coinciding intersection points using the diagonal segment ratios of base B. More...
|
|
int |
checkBaseMatch (const pcl::Indices &match_indices, const float(&ds)[4]) |
|
Check if outer rectangle distance of matched points fit with the base rectangle. More...
|
|
virtual void |
handleMatches (const pcl::Indices &base_indices, std::vector< pcl::Indices > &matches, MatchingCandidates &candidates) |
|
Method to handle current candidate matches. More...
|
|
virtual void |
linkMatchWithBase (const pcl::Indices &base_indices, pcl::Indices &match_indices, pcl::Correspondences &correspondences) |
|
Sets the correspondences between the base B and the match M by using the distance of each point to the centroid of the rectangle. More...
|
|
virtual int |
validateMatch (const pcl::Indices &base_indices, const pcl::Indices &match_indices, const pcl::Correspondences &correspondences, Eigen::Matrix4f &transformation) |
|
Validate the matching by computing the transformation between the source and target based on the four matched points and by comparing the mean square error (MSE) to a threshold. More...
|
|
virtual int |
validateTransformation (Eigen::Matrix4f &transformation, float &fitness_score) |
|
Validate the transformation by calculating the number of inliers after transforming the source cloud. More...
|
|
virtual void |
finalCompute (const std::vector< MatchingCandidates > &candidates) |
|
Final computation of best match out of vector of best matches. More...
|
|
bool |
searchForNeighbors (const PointCloudSource &cloud, int index, pcl::Indices &indices, std::vector< float > &distances) |
|
Search for the closest nearest neighbor of a given point. More...
|
|
virtual void |
computeTransformation (PointCloudSource &output, const Matrix4 &guess)=0 |
|
Abstract transformation computation method with initial guess. More...
|
|
bool |
initCompute () |
|
This method should get called before starting the actual computation. More...
|
|
bool |
deinitCompute () |
|
This method should get called after finishing the actual computation. More...
|
|
|
NormalsConstPtr |
source_normals_ |
|
Normals of source point cloud. More...
|
|
NormalsConstPtr |
target_normals_ |
|
Normals of target point cloud. More...
|
|
int |
nr_threads_ |
|
Number of threads for parallelization (standard = 1). More...
|
|
float |
approx_overlap_ |
|
Estimated overlap between source and target (standard = 0.5). More...
|
|
float |
delta_ |
|
Delta value of 4pcs algorithm (standard = 1.0). More...
|
|
float |
score_threshold_ |
|
Score threshold to stop calculation with success. More...
|
|
int |
nr_samples_ |
|
The number of points to uniformly sample the source point cloud. More...
|
|
float |
max_norm_diff_ |
|
Maximum normal difference of corresponding point pairs in degrees (standard = 90). More...
|
|
int |
max_runtime_ |
|
Maximum allowed computation time in seconds (standard = 0 => ~unlimited). More...
|
|
float |
fitness_score_ |
|
Resulting fitness score of the best match. More...
|
|
float |
diameter_ |
|
Estimated diamter of the target point cloud. More...
|
|
float |
max_base_diameter_sqr_ |
|
Estimated squared metric overlap between source and target. More...
|
|
bool |
use_normals_ |
|
Use normals flag. More...
|
|
bool |
normalize_delta_ |
|
Normalize delta flag. More...
|
|
pcl::IndicesPtr |
source_indices_ |
|
A pointer to the vector of source point indices to use after sampling. More...
|
|
pcl::IndicesPtr |
target_indices_ |
|
A pointer to the vector of target point indices to use after sampling. More...
|
|
float |
max_pair_diff_ |
|
Maximal difference between corresponding point pairs in source and target. More...
|
|
float |
max_edge_diff_ |
|
Maximal difference between the length of the base edges and valid match edges. More...
|
|
float |
coincidation_limit_ |
|
Maximal distance between coinciding intersection points to find valid matches. More...
|
|
float |
max_mse_ |
|
Maximal mean squared errors of a transformation calculated from a candidate match. More...
|
|
float |
max_inlier_dist_sqr_ |
|
Maximal squared point distance between source and target points to count as inlier. More...
|
|
const float |
small_error_ |
|
Definition of a small error. More...
|
|
std::string |
reg_name_ |
|
The registration method name. More...
|
|
KdTreePtr |
tree_ |
|
A pointer to the spatial search object. More...
|
|
KdTreeReciprocalPtr |
tree_reciprocal_ |
|
A pointer to the spatial search object of the source. More...
|
|
int |
nr_iterations_ |
|
The number of iterations the internal optimization ran for (used internally). More...
|
|
int |
max_iterations_ |
|
The maximum number of iterations the internal optimization should run for. More...
|
|
int |
ransac_iterations_ |
|
The number of iterations RANSAC should run for. More...
|
|
PointCloudTargetConstPtr |
target_ |
|
The input point cloud dataset target. More...
|
|
Matrix4 |
final_transformation_ |
|
The final transformation matrix estimated by the registration method after N iterations. More...
|
|
Matrix4 |
transformation_ |
|
The transformation matrix estimated by the registration method. More...
|
|
Matrix4 |
previous_transformation_ |
|
The previous transformation matrix estimated by the registration method (used internally). More...
|
|
double |
transformation_epsilon_ |
|
The maximum difference between two consecutive transformations in order to consider convergence (user defined). More...
|
|
double |
transformation_rotation_epsilon_ |
|
The maximum rotation difference between two consecutive transformations in order to consider convergence (user defined). More...
|
|
double |
euclidean_fitness_epsilon_ |
|
The maximum allowed Euclidean error between two consecutive steps in the ICP loop, before the algorithm is considered to have converged. More...
|
|
double |
corr_dist_threshold_ |
|
The maximum distance threshold between two correspondent points in source <-> target. More...
|
|
double |
inlier_threshold_ |
|
The inlier distance threshold for the internal RANSAC outlier rejection loop. More...
|
|
bool |
converged_ |
|
Holds internal convergence state, given user parameters. More...
|
|
int |
min_number_correspondences_ |
|
The minimum number of correspondences that the algorithm needs before attempting to estimate the transformation. More...
|
|
CorrespondencesPtr |
correspondences_ |
|
The set of correspondences determined at this ICP step. More...
|
|
TransformationEstimationPtr |
transformation_estimation_ |
|
A TransformationEstimation object, used to calculate the 4x4 rigid transformation. More...
|
|
CorrespondenceEstimationPtr |
correspondence_estimation_ |
|
A CorrespondenceEstimation object, used to estimate correspondences between the source and the target cloud. More...
|
|
std::vector< CorrespondenceRejectorPtr > |
correspondence_rejectors_ |
|
The list of correspondence rejectors to use. More...
|
|
bool |
target_cloud_updated_ |
|
Variable that stores whether we have a new target cloud, meaning we need to pre-process it again. More...
|
|
bool |
source_cloud_updated_ |
|
Variable that stores whether we have a new source cloud, meaning we need to pre-process it again. More...
|
|
bool |
force_no_recompute_ |
|
A flag which, if set, means the tree operating on the target cloud will never be recomputed. More...
|
|
bool |
force_no_recompute_reciprocal_ |
|
A flag which, if set, means the tree operating on the source cloud will never be recomputed. More...
|
|
std::function< UpdateVisualizerCallbackSignature > |
update_visualizer_ |
|
Callback function to update intermediate source point cloud position during it's registration to the target point cloud. More...
|
|
PointCloudConstPtr |
input_ |
|
The input point cloud dataset. More...
|
|
IndicesPtr |
indices_ |
|
A pointer to the vector of point indices to use. More...
|
|
bool |
use_indices_ |
|
Set to true if point indices are used. More...
|
|
bool |
fake_indices_ |
|
If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...
|
|
template<typename PointSource, typename PointTarget, typename NormalT = pcl::Normal, typename Scalar = float>
class pcl::registration::FPCSInitialAlignment< PointSource, PointTarget, NormalT, Scalar >
FPCSInitialAlignment computes corresponding four point congruent sets as described in: "4-points congruent sets for robust pairwise surface registration", Dror Aiger, Niloy Mitra, Daniel Cohen-Or.
ACM Transactions on Graphics, vol. 27(3), 2008
- Author
- P.W.Theiler
Definition at line 81 of file ia_fpcs.h.