mp2p_icp
A repertory of multi primitive-to-primitive (MP2P) ICP algorithms in C++
README
Distro |
Build dev |
Build releases |
Stable version |
|---|---|---|---|
ROS 2 Humble (u22.04) |
|||
ROS 2 Jazzy @ u24.04 |
|||
ROS 2 Kilted @ u24.04 |
|||
ROS 2 Rolling (u24.04) |
EOL Distro |
Last release |
|---|---|
ROS1 Noetic (u20.04) |
|
ROS 2 Iron (u22.04) |
mp2p_icp
C++ libraries for multi primitive-to-primitive (MP2P) ICP algorithms and flexible point cloud processing pipelines. mp2p_icp is used in the mola_lidar_odometry framework:
License: New BSD 3-Clause (Note that each module of MOLA has its own license)
Introduction
The project provides these C++ libraries:
mp2p_icp_map: Provides themp2p_icp::metric_map_tgeneric metric map container and related utilities for working with point cloud data structures. Metric map files with extension*.mmare serializations of instances of this class.mp2p_icp: With ICP algorithms, matchers (point-to-point, point-to-plane, point-to-line, covariance-to-covariance, adaptive), solvers (Horn, OLAE, Gauss-Newton), and quality evaluators. It depends onmp2p_icp_map.mp2p_icp_filters: With point cloud filtering and manipulation algorithms including decimation, voxelization, statistical outlier removal, edge/plane extraction, and various geometric transformations. It depends onmp2p_icp_map.
Command-Line Applications
The full repository also includes these applications (see apps/ directory):
Data Conversion Tools
kitti2mm: Converts KITTI dataset LIDAR binary files (
.bin) with (X,Y,Z, Intensity) data into mp2p_icp metric map files (.mm). Supports custom layer names, numeric IDs, and label strings.txt2mm: Converts plain-text point cloud data (TXT/CSV) into metric map (
.mm) files. Supports multiple formats: XYZ, XYZI, XYZIRT, XYZRGB, with configurable column mapping and layer names.sm2mm: Converts a simple map (
.simplemap) from a SLAM mapping session into a metric map (.mm) using a configurable processing pipeline. Essential for post-processing SLAM outputs into structured metric representations.
Data Export Tools
mm2ply: Exports metric map layers to PLY point cloud files. Supports both ASCII and binary formats, selective field export, and preserves all point attributes (coordinates, colors, intensities, etc.).
mm2txt: Exports metric map layers as space-delimited CSV/TXT files with header rows. Ideal for data analysis in spreadsheet applications or custom processing pipelines. Supports selective layer and field export.
mm2las: Exports metric maps to industry-standard LAS 1.4 format with Point Format 8 support. Includes automatic color mapping, extra dimensions for custom fields. Compatible with CloudCompare, QGIS, and ArcGIS.
Map Processing & Analysis Tools
mm-filter: Applies mp2p_icp_filters pipelines to metric map files. Can operate in pipeline mode (applying complete YAML-defined filter chains) or rename mode (simply renaming layers). Supports custom plugin loading.
mm-info: Displays a summary of metric map contents including layers, point counts, and metadata.
mm-georef: Extracts or injects geo-referencing information between metric map files (
.mm) and standalone georeferencing files (.georef).
Visualization Tools
mm-viewer: GUI application to visualize metric map (
.mm) files. Supports loading additional 3D scenes and trajectory files in TUM format.icp-log-viewer: Interactive GUI for debugging ICP pipelines. Visualizes ICP log files (
.icplog) with autoplay mode and detailed inspection of registration results. Essential for understanding and optimizing ICP algorithm performance.
ICP Execution Tools
icp-run: Standalone program to execute ICP pipelines from the command line.
SimpleMaps Manipulation
sm-cli: Swiss-army knife for simple map (
.simplemap) manipulation. Commands include:info(analyze contents),cut(extract by keyframe index),trim(extract by bounding box),join(merge maps),level(make horizontal),tf(apply SE(3) transform),export-keyframes(save trajectories as TUM), andexport-rawlog(convert to RawLog format).
Key Features and Components
Key C++ classes provided by this project (see full documentation):
Core Data Structures
mp2p_icp::metric_map_t: A generic data type to store raw or processed point clouds, including support for multiple layers, segmented data, and discrete extracted features.
ICP Algorithms and Matchers
mp2p_icp::ICP: A uniform API for matching generic point clouds with support for:Point-to-Point matching (various distance metrics)
Point-to-Plane matching (planes extracted from point clouds)
Point-to-Line matching (edges/lines extracted from point clouds)
Covariance-to-Covariance matching (Gaussian distributions)
Adaptive matching (automatically selects best matcher)
Solvers
Horn’s method: Closed-form solution for point-to-point alignment
OLAE (Optimal Linear Attitude Estimator): For attitude/rotation estimation
Gauss-Newton: Iterative solver for complex matching scenarios
Filters and Generators
The mp2p_icp_filters library provides extensive filtering capabilities:
Decimation:
FilterDecimate,FilterDecimateVoxels,FilterDecimateAdaptiveOutlier removal:
FilterSOR(Statistical Outlier Removal),FilterVoxelSORGeometric filtering:
FilterByRange,FilterBoundingBox,FilterByRingFeature extraction:
FilterEdgesPlanes,FilterCurvatureData manipulation:
FilterDeskew,FilterMerge,FilterAdjustTimestampsGenerators:
GeneratorEdgesFromCurvature,GeneratorEdgesFromRangeImage
Quality Evaluators
QualityEvaluator_PairedRatio: Evaluates alignment quality based on paired point ratiosQualityEvaluator_Voxels: Voxel-based quality metricsQualityEvaluator_RangeImageSimilarity: Range image comparison metrics
Multi-Primitive Pairings
The library supports matching between different geometric primitives (points, planes, lines, covariances), allowing for more robust and accurate registration compared to traditional point-to-point ICP. See the documentation for more details on the pairing strategies and matching algorithms.
