KCP
An efficient and effective 3D laser scan matching
Remarks

Tuning Parameters

The major parameters are

where k is the number of nearest points of each source point selected to be part of initial correspondences, and noise_bound is the criterion to determine if a correspondence is correct. In our paper, we suggest k=2 and noise_bound the 3-sigma (we use noise_bound=0.06 meters for nuScenes data), and those are default values in the library.

There is also a boolean parameter to enable debug messages called kcp::KCP::Params::verbose (default: false).

To use different parameters to the KCP solver, please refer to the following snippets:

C++

#include <kcp/solver.hpp>
auto params = kcp::KCP::Params();
params.k = 2;
params.verbose = false;
params.teaser.noise_bound = 0.06;
auto solver = kcp::KCP(params);
The KCP-TEASER registration approach.
Definition: solver.hpp:68
Type of parameters for the KCP-TEASER solver.
Definition: solver.hpp:80

Python

import pykcp
params = pykcp.KCPParams()
params.k = 2
params.verbose = False
params.teaser.noise_bound = 0.06
solver = pykcp.KCP(params)

Controlling Computational Cost

Instead of correspondence-free registration in TEASER++, KCP considers k closest point correspondences to reduce the major computational cost of the maximum clique algorithm, and we have expressed the ability for real-world scenarios without any complicate or learning-based feature descriptor in the paper. However, it is still possible to encounter computational time or memory issue if there are too many correspondences fed to the solver.

We suggest controlling your keypoints around 500 for k=2 (in this way the computational time will be much closer to the one presented in the paper).

Torwarding Global Registration Approaches

It is promising that KCP can be extended to a global registration approach if a fast and reliable sparse feature point representation method is employed.

In this way, the role of RANSAC, a fast registration approach usually used in learning based approaches, is similar to KCP's, but the computation results of KCP are deterministic, and also, KCP has better theoretical supports.