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 <optional>
16
17#include "geo.h"
18
19namespace icp {
48 class ICP {
49 protected:
51 struct Match {
52 size_t point;
53 size_t pair;
54 double cost;
55 };
56
59
61 std::vector<Vector> a;
62
64 std::vector<Vector> b;
65
67 std::vector<Match> matches;
68
69 ICP();
70
76 virtual void setup() = 0;
77
78 public:
80 class Config {
81 using Param = std::variant<int, double, std::string>;
82 std::unordered_map<std::string, Param> params;
83
84 public:
86 Config() {}
87
89 template<typename T>
90 void set(std::string key, T value) {
91 params[key] = value;
92 }
93
96 template<typename T>
97 T get(std::string key, T otherwise) const {
98 if (params.find(key) == params.end()) {
99 return otherwise;
100 } else {
101 return std::get<T>(params.at(key));
102 }
103 }
104 };
105
106 virtual ~ICP() = default;
107
110 void begin(const std::vector<Vector>& a, const std::vector<Vector>& b, RBTransform t);
111
118 virtual void iterate() = 0;
119
126 double calculate_cost() const;
127
129 const RBTransform& current_transform() const;
130
133 static bool register_method(std::string name,
134 std::function<std::unique_ptr<ICP>(const Config&)> constructor);
135
137 static bool is_method_registered(std::string name);
138
141 static const std::vector<std::string>& registered_methods();
142
150 static std::optional<std::unique_ptr<ICP>> from_method(std::string name,
151 const Config& params = Config());
152
153 private:
154 struct Methods {
155 std::vector<std::string> registered_method_names;
156 std::vector<std::function<std::unique_ptr<ICP>(const ICP::Config&)>>
157 registered_method_constructors;
158 };
159
160 static Methods global;
161 static bool builtins_registered;
162
165 static void ensure_builtins_registered();
166
168 static void register_method_internal(std::string name,
169 std::function<std::unique_ptr<ICP>(const Config&)> constructor);
170 };
171}
Configuration for ICP instances.
Definition icp.h:80
Config()
Constructs an empty configuration.
Definition icp.h:86
T get(std::string key, T otherwise) const
Retrieves the integer, double, or string value associated with key.
Definition icp.h:97
void set(std::string key, T value)
Associates key with an integer, double, or string value.
Definition icp.h:90
Interface for iterative closest points.
Definition icp.h:48
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:50
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
virtual void setup()=0
Per-method setup code.
Definition icp.cpp:18
RBTransform transform
The current point cloud transformation that is being optimized.
Definition icp.h:58
static bool is_method_registered(std::string name)
Returns true if the ICP method name is registered.
Definition icp.cpp:62
ICP()
Definition icp.cpp:16
std::vector< Vector > a
The source point cloud.
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:70
std::vector< Vector > b
The destination point cloud.
Definition icp.h:64
std::vector< Match > matches
The pairing of each point in a to its closest in b.
Definition icp.h:67
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:20
const RBTransform & current_transform() const
The current transform.
Definition icp.cpp:43
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:35
Definition driver.h:7
A matching between point and pair at (arbitrary) cost cost.
Definition icp.h:51
size_t pair
Definition icp.h:53
size_t point
Definition icp.h:52
double cost
Definition icp.h:54
Rigid-body transformation.
Definition geo.h:19