iterative closest points
CEV ICP algorithm library
Loading...
Searching...
No Matches
icp.cpp
Go to the documentation of this file.
1/*
2 * @author Ethan Uppal
3 * @copyright Copyright (C) 2024 Ethan Uppal. All rights reserved.
4 */
5
6#include <numeric>
7#include "icp.h"
8
9namespace icp {
10 static Methods* global;
11
13
14 void ICP::setup() {}
15
16 void ICP::begin(const std::vector<Vector>& a, const std::vector<Vector>& b, RBTransform t) {
17 // Initial transform guess
18 this->transform = t;
19
20 // Copy in point clouds
21 this->a = a;
22 this->b = b;
23
24 // Cost is infinite initially
25 previous_cost = std::numeric_limits<double>::infinity();
26 current_cost = std::numeric_limits<double>::infinity();
27
28 // Ensure arrays are the right size
29 const size_t n = this->a.size();
30 if (matches.size() < n) {
31 matches.resize(n);
32 }
33
34 // Per-instance customization routine
35 setup();
36 }
37
38 double ICP::calculate_cost() const {
39 double sum_squares{};
40 for (auto& match: matches) {
41 sum_squares += match.sq_dist;
42 }
43 return std::sqrt(sum_squares / a.size());
44 }
45
46 ICP::ConvergenceReport ICP::converge(size_t burn_in, double convergence_threshold) {
47 ConvergenceReport result{};
48
49 // Repeat until convergence
50 while (current_cost > convergence_threshold || current_cost == INFINITY
51 || result.iteration_count < burn_in) {
52 // Store previous iteration results
54 RBTransform previous_transform = transform;
55
56 iterate();
57
58 // If cost rose, revert to previous transformation/cost and
59 // exit
61 if (current_cost >= previous_cost && result.iteration_count > burn_in) {
62 transform = previous_transform;
64 break;
65 }
66
67 result.iteration_count++;
68 }
69
70 result.final_cost = current_cost;
71
72 return result;
73 }
74
76 return transform;
77 }
78
79 static void ensure_methods_exists() {
80 if (!global) {
81 global = new Methods();
82 }
83 }
84
85 bool ICP::register_method(std::string name,
86 std::function<std::unique_ptr<ICP>(const ICP::Config&)> constructor) {
87 ensure_methods_exists();
88 global->registered_method_constructors.push_back(constructor);
89 global->registered_method_names.push_back(name);
90 return true;
91 }
92
93 const std::vector<std::string>& ICP::registered_methods() {
94 ensure_methods_exists();
95 return global->registered_method_names;
96 }
97
98 std::unique_ptr<ICP> ICP::from_method(std::string name, const ICP::Config& config) {
99 ensure_methods_exists();
100 size_t index = std::find(global->registered_method_names.begin(),
101 global->registered_method_names.end(), name)
102 - global->registered_method_names.begin();
103 return global->registered_method_constructors[index](config);
104 }
105
106 bool ICP::is_registered_method(std::string name) {
107 return std::find(global->registered_method_names.begin(),
108 global->registered_method_names.end(), name)
109 != global->registered_method_names.end();
110 }
111}
Configuration for ICP instances.
Definition icp.h:92
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 ...
Definition icp.cpp:85
double previous_cost
Keeps track of the previous cost to ensure that progress is being made.
Definition icp.h:68
virtual void setup()
Definition icp.cpp:14
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:98
RBTransform transform
The current point cloud transformation that is being optimized.
Definition icp.h:58
ICP()
Definition icp.cpp:12
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...
Definition icp.cpp:46
double current_cost
The RMS (root mean square) cost of the current transformation.
Definition icp.h:71
std::vector< Vector > a
The source point cloud relative to its centroid.
Definition icp.h:61
static const std::vector< std::string > & registered_methods()
Returns a current list of the names of currently registered ICP methods.
Definition icp.cpp:93
std::vector< Vector > b
The destination point cloud relative to its centroid.
Definition icp.h:64
std::vector< Match > matches
The pairing of each point in a to its closest in b.
Definition icp.h:74
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.
Definition icp.cpp:16
const RBTransform & current_transform() const
The current transform.
Definition icp.cpp:75
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.
Definition icp.cpp:38
static bool is_registered_method(std::string name)
Whether name is a registered ICP method.
Definition icp.cpp:106
Definition geo.cpp:9
The result of running ICP::converge.
Definition icp.h:82
std::vector< std::function< std::unique_ptr< ICP >(const ICP::Config &)> registered_method_constructors)
Definition icp.h:178
std::vector< std::string > registered_method_names
Definition icp.h:176
Rigid-body transformation.
Definition geo.h:19