iterative closest points
CEV ICP algorithm library
Loading...
Searching...
No Matches
icp.h
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#pragma once
7
8#include <cmath>
9#include <vector>
10#include <memory>
11#include <string>
12#include <functional>
13#include <unordered_map>
14#include <variant>
15#include "geo.h"
16
17namespace icp {
45 class ICP {
46 protected:
47 // TODO: make this more general to allow for point-to-line
50 struct Match {
51 size_t point;
52 size_t pair;
53 double sq_dist;
54 };
55
59
61 std::vector<Vector> a;
62
64 std::vector<Vector> b;
65
69
72
74 std::vector<Match> matches;
75
76 ICP();
77
78 virtual void setup();
79
80 public:
84 double final_cost;
85
89 };
90
92 class Config {
93 using Param = std::variant<int, double, std::string>;
94 std::unordered_map<std::string, Param> params;
95
96 public:
98 Config() {}
99
101 template<typename T>
102 void set(std::string key, T value) {
103 params[key] = value;
104 }
105
108 template<typename T>
109 T get(std::string key, T otherwise) const {
110 if (params.find(key) == params.end()) {
111 return otherwise;
112 } else {
113 return std::get<T>(params.at(key));
114 }
115 }
116 };
117
118 virtual ~ICP() = default;
119
122 void begin(const std::vector<Vector>& a, const std::vector<Vector>& b, RBTransform t);
123
128 virtual void iterate() = 0;
129
136 double calculate_cost() const;
137
148 ConvergenceReport converge(size_t burn_in, double convergence_threshold);
149
151 const RBTransform& current_transform() const;
152
155 static bool register_method(std::string name,
156 std::function<std::unique_ptr<ICP>(const Config&)> constructor);
157
160 static const std::vector<std::string>& registered_methods();
161
169 static std::unique_ptr<ICP> from_method(std::string name, const Config& params = Config());
170
172 static bool is_registered_method(std::string name);
173 };
174
175 struct Methods {
176 std::vector<std::string> registered_method_names;
177 std::vector<std::function<std::unique_ptr<ICP>(const ICP::Config&)>>
179 };
180}
Configuration for ICP instances.
Definition icp.h:92
Config()
Constructs an empty configuration.
Definition icp.h:98
T get(std::string key, T otherwise) const
Retrieves the integer, double, or string value associated with key.
Definition icp.h:109
void set(std::string key, T value)
Associates key with an integer, double, or string value.
Definition icp.h:102
Interface for iterative closest points.
Definition icp.h:45
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
virtual ~ICP()=default
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
size_t iteration_count
The number of iterations performed, including the burn-in period.
Definition icp.h:88
double final_cost
The least cost achieved.
Definition icp.h:84
A point-to-point matching between point and pair at a distance of sqrt(sq_dist).
Definition icp.h:50
size_t pair
Definition icp.h:52
double sq_dist
Definition icp.h:53
size_t point
Definition icp.h:51
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