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>

Inheritance diagram for icp::ICP:
icp::FeatureAware icp::Trimmed icp::Vanilla

Classes

class  Config
 Configuration for ICP instances. More...
 
struct  Match
 A matching between point and pair at (arbitrary) cost cost. 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.
 
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 bool is_method_registered (std::string name)
 Returns true if the ICP method name is registered.
 
static const std::vector< std::string > & registered_methods ()
 Returns a current list of the names of currently registered ICP methods.
 
static std::optional< std::unique_ptr< ICP > > from_method (std::string name, const Config &params=Config())
 Factory constructor for the ICP method name with configuration config.
 

Protected Member Functions

 ICP ()
 
virtual void setup ()=0
 Per-method setup code.
 

Protected Attributes

RBTransform transform
 The current point cloud transformation that is being optimized.
 
std::vector< Vectora
 The source point cloud.
 
std::vector< Vectorb
 The destination point cloud.
 
std::vector< Matchmatches
 The pairing of each point in a to its closest in b.
 

Detailed Description

Interface for iterative closest points.

Generally, you should interact with ICP instances through this interface or ICPDriver, though interacting with implementations directly isn't explicitly disallowed. 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::optional< 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:76
Definition driver.h:7
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. Repeatedly call icp->iterate() until convergence. ICPDriver can also be used to specify convergence conditions.

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 48 of file icp.h.

Constructor & Destructor Documentation

◆ ICP()

icp::ICP::ICP ( )
protected

Definition at line 16 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 20 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 35 of file icp.cpp.

◆ current_transform()

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

The current transform.

Definition at line 43 of file icp.cpp.

◆ from_method()

std::optional< 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::registered_methods.

Definition at line 76 of file icp.cpp.

◆ is_method_registered()

bool icp::ICP::is_method_registered ( std::string  name)
static

Returns true if the ICP method name is registered.

Definition at line 62 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.
Postcondition
For implementers: must fill matches with newest match data.

Implemented in icp::FeatureAware, icp::Trimmed, and icp::Vanilla.

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

◆ setup()

void icp::ICP::setup ( )
protectedpure virtual

Per-method setup code.

Postcondition
For implementers: must fill matches with match data for the initial point clouds.

Implemented in icp::FeatureAware, icp::Trimmed, and icp::Vanilla.

Definition at line 18 of file icp.cpp.

Member Data Documentation

◆ a

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

The source point cloud.

Definition at line 61 of file icp.h.

◆ b

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

The destination point cloud.

Definition at line 64 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 67 of file icp.h.

◆ transform

RBTransform icp::ICP::transform
protected

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: