Interface for iterative closest points.
More...
#include <icp.h>
Inherited by icp::Trimmed, and icp::Vanilla.
|
virtual | ~ICP ()=default |
|
void | begin (const std::vector< Vector > &a, const std::vector< Vector > &b, RBTransform t) |
| Begins the ICP process for point clouds a and b with an initial guess for the transform t .
|
|
virtual void | iterate ()=0 |
| Perform one iteration of ICP for the point clouds a and b provided with ICP::begin.
|
|
double | calculate_cost () const |
| Computes the cost of the current transformation.
|
|
ConvergenceReport | converge (size_t burn_in, double convergence_threshold) |
| Perform ICP for the point clouds a and b provided with ICP::begin until the cost is below convergence_threshold or until no progress is being made.
|
|
const RBTransform & | current_transform () const |
| The current transform.
|
|
|
static bool | register_method (std::string name, std::function< std::unique_ptr< ICP >(const Config &)> constructor) |
| Registers a new ICP method that can be created with constructor , returning false if name has already been registered.
|
|
static const std::vector< std::string > & | registered_methods () |
| Returns a current list of the names of currently registered ICP methods.
|
|
static std::unique_ptr< ICP > | from_method (std::string name, const Config ¶ms=Config()) |
| Factory constructor for the ICP method name with configuration config .
|
|
static bool | is_registered_method (std::string name) |
| Whether name is a registered ICP method.
|
|
|
RBTransform | transform |
| The current point cloud transformation that is being optimized.
|
|
std::vector< Vector > | a |
| The source point cloud relative to its centroid.
|
|
std::vector< Vector > | b |
| The destination point cloud relative to its centroid.
|
|
double | previous_cost |
| Keeps track of the previous cost to ensure that progress is being made.
|
|
double | current_cost |
| The RMS (root mean square) cost of the current transformation.
|
|
std::vector< Match > | matches |
| The pairing of each point in a to its closest in b .
|
|
Interface for iterative closest points.
You should interact with ICP instances through this API only. Read Writing an ICP Instance for additional information.
- Example
static std::unique_ptr< ICP > from_method(std::string name, const Config ¶ms=Config())
Factory constructor for the ICP method name with configuration config.
- Usage
- Let
a
and b
be two point clouds of type std::vector<Vector>
. Then, given an ICP instance icp
of type std::unique_ptr<icp::ICP>
, perform the following steps.
- Call
icp->begin(a, b, initial_guess)
.
- Call either
icp->converge(convergence_threshold)
or repeatedly icp->iterate()
.
If these steps are not followed as described here, the behavior is undefined.
At any point in the process, you may query icp->calculate_cost()
and icp->transform()
. Do note, however, that icp->calculate_cost()
is not a constant-time operation.
Definition at line 45 of file icp.h.
◆ ICP()
◆ ~ICP()
virtual icp::ICP::~ICP |
( |
| ) |
|
|
virtualdefault |
◆ begin()
Begins the ICP process for point clouds a
and b
with an initial guess for the transform t
.
Definition at line 16 of file icp.cpp.
◆ calculate_cost()
double icp::ICP::calculate_cost |
( |
| ) |
const |
Computes the cost of the current transformation.
- Efficiency:
O(a.size())
where a
is the source point cloud.
Definition at line 38 of file icp.cpp.
◆ converge()
Perform ICP for the point clouds a
and b
provided with ICP::begin until the cost is below convergence_threshold
or until no progress is being made.
At least burn_in
iterations will be performed. Start with zero burn-in, and slowly increase if convergence requirements are not met.
- Returns
- Information about the convergence.
- Precondition
- ICP::begin must have been invoked.
Definition at line 46 of file icp.cpp.
◆ current_transform()
const RBTransform & icp::ICP::current_transform |
( |
| ) |
const |
The current transform.
Definition at line 75 of file icp.cpp.
◆ from_method()
std::unique_ptr< ICP > icp::ICP::from_method |
( |
std::string | name, |
|
|
const Config & | params = Config() ) |
|
static |
Factory constructor for the ICP method name
with configuration config
.
- Precondition
name
is a valid registered method. See ICP::is_registered_method.
Definition at line 98 of file icp.cpp.
◆ is_registered_method()
bool icp::ICP::is_registered_method |
( |
std::string | name | ) |
|
|
static |
Whether name
is a registered ICP method.
Definition at line 106 of file icp.cpp.
◆ iterate()
virtual void icp::ICP::iterate |
( |
| ) |
|
|
pure virtual |
Perform one iteration of ICP for the point clouds a
and b
provided with ICP::begin.
- Precondition
- ICP::begin must have been invoked.
◆ register_method()
bool icp::ICP::register_method |
( |
std::string | name, |
|
|
std::function< std::unique_ptr< ICP >(const Config &)> | constructor ) |
|
static |
Registers a new ICP method that can be created with constructor
, returning false
if name
has already been registered.
Definition at line 85 of file icp.cpp.
◆ registered_methods()
const std::vector< std::string > & icp::ICP::registered_methods |
( |
| ) |
|
|
static |
Returns a current list of the names of currently registered ICP methods.
Definition at line 93 of file icp.cpp.
◆ setup()
std::vector<Vector> icp::ICP::a |
|
protected |
The source point cloud relative to its centroid.
Definition at line 61 of file icp.h.
std::vector<Vector> icp::ICP::b |
|
protected |
The destination point cloud relative to its centroid.
Definition at line 64 of file icp.h.
◆ current_cost
double icp::ICP::current_cost |
|
protected |
The RMS (root mean square) cost of the current transformation.
Definition at line 71 of file icp.h.
◆ matches
std::vector<Match> icp::ICP::matches |
|
protected |
The pairing of each point in a
to its closest in b
.
Definition at line 74 of file icp.h.
◆ previous_cost
double icp::ICP::previous_cost |
|
protected |
Keeps track of the previous cost to ensure that progress is being made.
- See also
- ICP::current_cost.
Definition at line 68 of file icp.h.
◆ transform
The current point cloud transformation that is being optimized.
Definition at line 58 of file icp.h.
The documentation for this class was generated from the following files: