from http://github.com/ethz-asl/libpointmatcher by François Pomerleau and Stéphane Magnenat (http://stephane.magnenat.net), ASL-ETHZ, Switzerland (http://www.asl.ethz.ch)
libpointmatcher is a modular ICP library, useful for robotics and computer vision. This help assumes that libpointmatcher is already installed, if not, please read the README.md
file at the top-level of the source tree.
To test, you can use the pmicp
command provided in the example
directory, or installed system-wide with the -bin
deb package.
In 2D:
pmicp ${SRC_DIR}/examples/data/2D_oneBox.csv ${SRC_DIR}/examples/data/data/2D_twoBoxes.csv
In 3D:
pmicp ${SRC_DIR}/examples/data/car_cloud401.csv ${SRC_DIR}/examples/data/car_cloud400.csv
Use Paraview to view the results. On Ubuntu, you can install Paraview with:
sudo apt-get install paraview
You can list the available modules with:
pmicp -l
If you have compiled libpointmatcher with yaml-cpp enabled, you can configure the ICP chain without any recompilation by passing a configuration file to the pmicp
command using the --config
switch. An example file is available in examples/data/default.yaml
.
This library implements a modular ICP chain. ICP is an iterative algorithm performing several sequential processing steps, both inside and outside its main loop. For each step, there exist several strategies, and each strategy demands specific parameters. In libpointmatcher, every module is a class that can describe its own possible parameters, therefore enabling the whole chain to be configured at run time using YAML . This text-based configuration aids to explicit parameters used and eases the sharing of working setups with others, which ultimately allows for reproducibility and reusability of the solutions.
The ICP chain takes as input two point clouds, in 2D or 3D, and estimates the translation and the rotation parameters that minimize the alignment error. We called the first point cloud the reference and the second the reading. The ICP algorithm tries to align the reading onto the reference. To do so, it first applies filtering (PointMatcher::DataPointsFilters) to the point clouds, and then it iterates through a sequence of processing blocks. For each iteration, it associates points in reading to points in reference (PointMatcher::Matcher), rejects outliers (PointMatcher::OutlierFilters) and finds a transformation (PointMatcher::TransformationParameters) of reading that minimizes the alignment error (PointMatcher::ErrorMinimizer).
All modules are children of parent classes defined within the PointMatcher class. This class is templatized on the scalar type for the point coordinates, typically float
or double
. Additionally, the PointMatcherSupport namespace hosts classes that do not depend on the template parameter. Every kind of module has its own pair of .h and .cpp files. Because modules can enumerate their parameters at run time, only the parent classes lie in the publicly accessible header PointMatcher.h. This maintains a lean and easy-to-learn API.
To use libpointmatcher from a third-party program, the two classes PointMatcher::ICP and PointMatcher::ICPSequence can be instantiated. The first provides a basic registration between a reading and a reference, given an initial transformation. The second provides a tracker-style interface: an instance of this class receives several point clouds in sequence and continuously updates the transformation with respect to a user-provided point cloud. This is useful to limit drift due to noise in the case of high-frequency sensors such as RGB-D camera. A common base class, PointMatcher::ICPChainBase, holds the instances of the modules and provides the loading mechanism.
When doing research, it is crucial to understand what is going on, in particular in complex processing pipelines like the ICP chain. Therefore, libpointmatcher provides two inspection mechanisms: the PointMatcherSupport::Logger and the PointMatcher::Inspector. The logger is responsible for writing information during execution to a file or to the console. It will typically display light statistics and warnings. The inspector provides deeper scrutiny than the logger. There are several instances of inspectors in libpointmatcher. For instance, one dumps ICP operations as VTK files, allowing to visualize the inner loop of the algorithm frame by frame. Another inspector collects statistics for performance evaluation.
If you wish to develop using libpointmatcher, you can start by looking at the sources of icp_simple and pmicp (in example/icp_simple.cpp
and example/icp.cpp
). You can see how loading/saving of data files work by looking at convert (example/convert.cpp
). If you want to see how libpointmatcher can align a sequence of clouds, you can have a look at align_sequence (example/align_sequence.cpp
).
You can also extend libpointmatcher relatively easily, by adding new modules. The file PointMatcher.h is the most important file, it defines the interfaces for all module types, as well as the ICP algorithms. Each interface is an inner class of the PointMatcher class, which is templatized on the scalar type. Instanciation is forced in Registry.cpp
for float and double scalar types. There are different types of modules corresponding to the different bricks of the ICP algorithm. The modules themselves are defined in their own files, for instance data-point filters live in the DataPointFiltersImpl.h/
files. Start from the documentation of PointMatcher to see the different interfaces, and then read the source code of the existing modules for the interface you are interested in, to get an idea of what you have to implement..cpp
All modules have a common way to get parameters at initialization (Parametrizable), and feature a self-documentation mechanism. This allows to configure the ICP chain from external descriptions such as yaml files.
You have to modify 3 files to add a new DataPointsFilter: DataPointsFiltersImpl.h
, DataPointsFiltersImpl.cpp
and Registry.cpp
. The easiest way is to start by copying and renaming IdentityDataPointsFilter
, and then to modify it.
DataPointsFiltersImpl.h
, copy the declaration of the struct IdentityDataPointsFilter
at the end of the file.description()
function with a short explanation of the filter's action.availableParameters()
function and fill the description, default, min, max values as string.&P::Comp<T>
, &P::Comp<int>
, &P::Comp<unsigned>
, etc. See DataPointsFiltersImpl.h
for examples.DataPointsFiltersImpl.cpp
, copy the implementation of IdentityDataPointsFilter
at the end of the file including the explicit instantiation (i.e. template
struct
DataPointsFiltersImpl<float>::YourFilter
; and template
struct
DataPointsFiltersImpl<double>::YourFilter
;).Registry.cpp
, search for "ADD_TO_REGISTRAR(DataPointsFilter,"
.DataPointsFilter
there. At the end of that block, add your filter.pmicp
-l
command, which lists the documentation of all modules. You should be able to find yours in the output.DataPointsFiltersImpl.cpp
and code the filter()
function.One shall:
For documentation, one shall document classes and data members inside the header file and methods at the implementation location. One exception is purely-virtual methods, which must be documented in the header file.
Please use github's issue tracker to report bugs.
If you use libpointmatcher in an academic context, please cite the following publication:
@INPROCEEDINGS{pomerleau11tracking,
author = {François Pomerleau and Stéphane Magnenat and Francis Colas and Ming Liu and Roland Siegwart},
title = {Tracking a Depth Camera: Parameter Exploration for Fast ICP},
booktitle = {Proc. of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
publisher = {IEEE Press},
pages = {3824--3829},
year = {2011}
}
libpointmatcher is released under a permissive BSD license.