iterative closest points
CEV ICP algorithm library
Loading...
Searching...
No Matches
Classes | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
icp::ICP Class Referenceabstract

Interface for iterative closest points. More...

#include <icp.h>

Inherited by icp::Test1, icp::Trimmed, and icp::Vanilla.

Classes

class  Config
 Configuration for ICP instances. More...
 
struct  ConvergenceReport
 The result of running ICP::converge. More...
 
struct  Match
 A point-to-point matching between point and pair at a distance of sqrt(sq_dist). More...
 

Public Member Functions

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 RBTransformcurrent_transform () const
 The current transform.
 

Static Public Member Functions

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< ICPfrom_method (std::string name, const Config &params=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.
 

Protected Member Functions

 ICP ()
 
virtual void setup ()
 

Protected Attributes

RBTransform transform
 The current point cloud transformation that is being optimized.
 
Vector a_cm
 The centroid of the source point cloud.
 
Vector b_cm
 The centroid of the destination point cloud.
 
std::vector< Vectora
 The source point cloud relative to its centroid.
 
std::vector< Vectorb
 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< Matchmatches
 The pairing of each point in a to its closest in b.
 

Detailed Description

Interface for iterative closest points.

You should interact with ICP instances through this API only. Read Writing an ICP Instance for additional information.

Example
// Construct a new vanilla ICP instance.
std::unique_ptr<icp::ICP> icp = icp::ICP::from_method("vanilla");
static std::unique_ptr< ICP > from_method(std::string name, const Config &params=Config())
Factory constructor for the ICP method name with configuration config.
Definition icp.cpp:112
Definition geo.cpp:9
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.
  1. Call icp->begin(a, b, initial_guess).
  2. 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 44 of file icp.h.

Constructor & Destructor Documentation

◆ ICP()

icp::ICP::ICP ( )
protected

Definition at line 12 of file icp.cpp.

◆ ~ICP()

virtual icp::ICP::~ICP ( )
virtualdefault

Member Function Documentation

◆ begin()

void icp::ICP::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.

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 50 of file icp.cpp.

◆ converge()

ICP::ConvergenceReport icp::ICP::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.

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 58 of file icp.cpp.

◆ current_transform()

const RBTransform & icp::ICP::current_transform ( ) const

The current transform.

Definition at line 89 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 112 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 121 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 99 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 107 of file icp.cpp.

◆ setup()

void icp::ICP::setup ( )
protectedvirtual

Definition at line 14 of file icp.cpp.

Member Data Documentation

◆ a

std::vector<Vector> icp::ICP::a
protected

The source point cloud relative to its centroid.

Definition at line 66 of file icp.h.

◆ a_cm

Vector icp::ICP::a_cm
protected

The centroid of the source point cloud.

Definition at line 60 of file icp.h.

◆ b

std::vector<Vector> icp::ICP::b
protected

The destination point cloud relative to its centroid.

Definition at line 69 of file icp.h.

◆ b_cm

Vector icp::ICP::b_cm
protected

The centroid of the destination point cloud.

Definition at line 63 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 76 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 79 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 73 of file icp.h.

◆ transform

RBTransform icp::ICP::transform
protected

The current point cloud transformation that is being optimized.

Definition at line 57 of file icp.h.


The documentation for this class was generated from the following files: