[Documentation] [TitleIndex] [WordIndex

ICP Chain Configuration

Modular Design

The registration chain performs a generalization of the Iterative Closest Point algorithm, based on the libpointmachter library. In this chain, a point cloud is a pair of vectors. The first vector is the feature vector, and typically holds the coordinates of the points. The second vector is the descriptor vector, and holds additional informations such as the normals to the points, their colors, etc. The descriptor vector is either empty or of the same size of the feature vector.

The registration chain takes two point clouds as input, the reading and the reference. The registration algorithm tries to align the reading onto the reference. To do so, it first applies some filtering to the cloud, and then iterates. In each iteration, it associates points in reading to points in reference and finds a transformation of reading such as to minimize an alignment error. The following sketch illustrates the process:

ICP chain

Data-Points Filters

A data-points filter takes a point cloud as input, transforms it, and produces another point cloud as output. For instance, the transformation might add descriptors, such as SurfaceNormalDataPointsFilter, or change the number of points, such as FixStepSamplingDataPointsFilter, or do both, such as SamplingSurfaceNormalDataPointsFilter.

Data-points filters can be chained.

Matchers

A matcher links points in the reading to points in the reference, for now, we provide KDTreeMatcher, based on the fast nearset-neighbor library libnabo.

Feature Outlier Filters

A feature outlier filter removes links between points in reading and their matched points in reference, depending on some criteria. For example, if the distance between the points exceeds a threshold, as in MaxDistOutlierFilter, or if it exceeds a certain number of times the median distance, as in MedianDistOutlierFilter.

Points with no link will be ignored in the subsequent minimization step. Feature outlier filters can be chained.

Error Minimizers

An error minimizer will compute a transformation matrix such as to minimize the error between the reading and the reference. There are different error functions available, such as PointToPointErrorMinimizer or PointToPlaneErrorMinimizer.

Transformation Checkers

A transformation checker can stop the iteration depending on some conditions. For example, a condition can be the number of times the loop was executed, as in CounterTransformationChecker, or it can be related to the matching error, as in DifferentialTransformationChecker.

Transformation checkers can be chained.

Inspector

The inspector allows to log data at the different steps, for analysis.

Available Modules

You configure the ICP chain through a yaml file. You can see an example for openni (launch/openni/icp.yaml of package ethzasl_icp_mapper). The rest of this section shows all available modules and their options. Note that you can retrieve this list using the pmicp -l command of package ethzasl_icp_mapper.

Note that some configurations are invalid, for instance, the PointToPlaneErrorMinimizer depends on the reference cloud having normals in its descriptors. Thus, to use this error minimizer, you must put SurfaceNormalDataPointsFilter or SamplingSurfaceNormalDataPointsFilter as data-point filters to the reference. If the ICP encounters an invalid chain, it will display an error message and abort.

Data-Points Filters

BoundingBoxDataPointsFilter

Subsampling. Remove points laying in a bounding box which is axis aligned.

xMin (default: -1, min: -inf, max: inf)

xMax (default: 1, min: -inf, max: inf)

yMin (default: -1, min: -inf, max: inf)

yMax (default: 1, min: -inf, max: inf)

zMin (default: -1, min: -inf, max: inf)

zMax (default: 1, min: -inf, max: inf)

removeInside (default: 1, min: 0, max: 1)

FixStepSamplingDataPointsFilter

Subsampling. This filter reduces the size of the point cloud by only keeping one point over step ones; with step varying in time from startStep to endStep, each iteration getting multiplied by stepMult. If use as prefilter (i.e. before the iterations), only startStep is used.

startStep (default: 10, min: 1, max: 2147483647)

endStep (default: 10, min: 1, max: 2147483647)

stepMult (default: 1, min: 0.0000001, max: inf)

MaxDensityDataPointsFilter

Subsampling. Reduce the points number by randomly removing points with a density highler than a treshold.

maxDensity (default: 10, min: 0.0000001, max: inf)

MaxDistDataPointsFilter

Subsampling. Filter points beyond a maximum distance measured on a specific axis. If dim is set to -1, points are filtered based on a maximum radius.

dim (default: -1, min: -1, max: 2)

maxDist (default: 1, min: -inf, max: inf)

MaxPointCountDataPointsFilter

Conditional subsampling. This filter reduces the size of the point cloud by randomly dropping points if their number is above maxCount. Based on [1]

prob (default: 0.75, min: 0, max: 1)

maxCount (default: 1000, min: 0, max: 2147483647)

MaxQuantileOnAxisDataPointsFilter

Subsampling. Filter points beyond a maximum quantile measured on a specific axis.

dim (default: 0, min: 0, max: 2)

ratio (default: 0.5, min: 0.0000001, max: 0.9999999)

MinDistDataPointsFilter

Subsampling. Filter points before a minimum distance measured on a specific axis. If dim is set to -1, points are filtered based on a minimum radius.

dim (default: -1, min: -1, max: 2)

minDist (default: 1, min: -inf, max: inf)

ObservationDirectionDataPointsFilter

Observation direction. This filter extracts observation directions (vector from point to sensor), considering a sensor at position (x,y,z).

x (default: 0)

y (default: 0)

z (default: 0)

OrientNormalsDataPointsFilter

Normals. Reorient normals so that they all point in the same direction, with respect to the observation points.

towardCenter (default: 1, min: 0, max: 1)

RandomSamplingDataPointsFilter

Subsampling. This filter reduces the size of the point cloud by randomly dropping points. Based on [1]

prob (default: 0.75, min: 0, max: 1)

RemoveNaNDataPointsFilter

Remove points having NaN as coordinate.

SamplingSurfaceNormalDataPointsFilter

Subsampling, Normals. This filter decomposes the point-cloud space in boxes, by recursively splitting the cloud through axis-aligned hyperplanes such as to maximize the evenness of the aspect ratio of the box. When the number of points in a box reaches a value knn or lower, the filter computes the center of mass of these points and its normal by taking the eigenvector corresponding to the smallest eigenvalue of all points in the box.

ratio (default: 0.5, min: 0.0000001, max: 0.9999999)

knn (default: 7, min: 3, max: 2147483647)

samplingMethod (default: 0, min: 0, max: 1)

maxBoxDim (default: inf)

averageExistingDescriptors (default: 1)

keepNormals (default: 1)

keepDensities (default: 0)

keepEigenValues (default: 0)

keepEigenVectors (default: 0)

ShadowDataPointsFilter

Remove ghost points appearing on edge discontinuties. Assume that the origine of the point cloud is close to where the laser center was. Requires surface normal for every points

eps (default: 0.1, min: 0.0, max: 3.1416)

SimpleSensorNoiseDataPointsFilter

Add a 1D descriptor named <sensorNoise> that would represent the noise radius expressed in meter based on SICK LMS specifications.

sensorType (default: 0, min: 0, max: 2147483647)

gain (default: 1, min: 1, max: inf)

SurfaceNormalDataPointsFilter

Normals. This filter extracts the normal to each point by taking the eigenvector corresponding to the smallest eigenvalue of its nearest neighbors.

knn (default: 5, min: 3, max: 2147483647)

epsilon (default: 0, min: 0, max: inf)

keepNormals (default: 1)

keepDensities (default: 0)

keepEigenValues (default: 0)

keepEigenVectors (default: 0)

keepMatchedIds (default: 0)

Matchers

KDTreeMatcher

This matcher matches a point from the reading to its closest neighbors in the reference.

knn (default: 1, min: 1, max: 2147483647)

epsilon (default: 0, min: 0, max: inf)

searchType (default: 1, min: 0, max: 2)

maxDist (default: inf, min: 0, max: inf)

KDTreeVarDistMatcher

This matcher matches a point from the reading to its closest neighbors in the reference. A maximum search radius per point can be defined.

knn (default: 1, min: 1, max: 2147483647)

epsilon (default: 0, min: 0, max: inf)

searchType (default: 1, min: 0, max: 2)

maxDistField (default: maxSearchDist)

Outlier Filters

MaxDistOutlierFilter

This filter considers as outlier links whose norms are above a fix threshold.

maxDist (default: 1, min: 0.0000001, max: inf)

MedianDistOutlierFilter

This filter considers as outlier links whose norms are above the median link norms times a factor. Based on [2].

factor (default: 3, min: 0.0000001, max: inf)

MinDistOutlierFilter

This filter considers as outlier links whose norms are below a threshold.

minDist (default: 1, min: 0.0000001, max: inf)

SurfaceNormalOutlierFilter

Hard rejection threshold using the angle between the surface normal vector of the reading and the reference. If normal vectors or not in the descriptor for both of the point clouds, does nothing.

maxAngle (default: 1.57, min: 0.0, max: 3.1416)

TrimmedDistOutlierFilter

Hard rejection threshold using quantile. This filter considers as inlier a certain percentage of the links with the smallest norms. Based on [3].

ratio (default: 0.85, min: 0.0000001, max: 0.9999999)

VarTrimmedDistOutlierFilter

Hard rejection threshold using quantile and variable ratio. Based on [4].

minRatio (default: 0.05, min: 0.0000001, max: 1)

maxRatio (default: 0.99, min: 0.0000001, max: 1)

lambda (default: 0.95)

Error Minimizers

IdentityErrorMinimizer

Does nothing.

PointToPlaneErrorMinimizer

Point-to-plane error (or point-to-line in 2D). Based on [5]

PointToPointErrorMinimizer

Point-to-point error. Based on SVD decomposition. Based on [6].

Transformation Checkers

BoundTransformationChecker

This checker stops the ICP loop with an exception when the transformation values exceed bounds.

maxRotationNorm (default: 1, min: 0, max: inf)

maxTranslationNorm (default: 1, min: 0, max: inf)

CounterTransformationChecker

This checker stops the ICP loop after a certain number of iterations.

maxIterationCount (default: 40, min: 0, max: 2147483647)

DifferentialTransformationChecker

This checker stops the ICP loop when the relative motions (i.e. abs(currentIter - lastIter)) of rotation and translation components are below a fix thresholds. This allows to stop the iteration when the point cloud is stabilized. Smoothing can be applied to avoid oscillations. Inspired by [3].

minDiffRotErr (default: 0.001, min: 0., max: 6.2831854)

minDiffTransErr (default: 0.001, min: 0., max: inf)

smoothLength (default: 3, min: 0, max: 2147483647)

Inspectors

NullInspector

Does nothing.

PerformanceInspector

Keep statistics on performance.

baseFileName (default: )

dumpPerfOnExit (default: 0)

VTKFileInspector

Dump the different steps into VTK files.

baseFileName (default: point-matcher-output)

dumpPerfOnExit (default: 0)

Bibliography


2024-04-13 12:37