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
8#include "icp/icp.h"
9
10// methods for builtin registration
11#include "icp/impl/vanilla.h"
12#include "icp/impl/trimmed.h"
14
15namespace icp {
17
18 void ICP::setup() {}
19
20 void ICP::begin(const std::vector<Vector>& a, const std::vector<Vector>& b, RBTransform t) {
21 // Initial transform guess
22 this->transform = t;
23
24 // Copy in point clouds
25 this->a = a;
26 this->b = b;
27
28 // Ensure arrays are the right size
29 matches.resize(this->a.size());
30
31 // Per-instance customization routine
32 setup();
33 }
34
35 double ICP::calculate_cost() const {
36 double sum_squares{};
37 for (auto& match: matches) {
38 sum_squares += match.cost;
39 }
40 return std::sqrt(sum_squares / a.size());
41 }
42
44 return transform;
45 }
46
47 ICP::Methods ICP::global;
48 bool ICP::builtins_registered = false;
49
50 bool ICP::register_method(std::string name,
51 std::function<std::unique_ptr<ICP>(const ICP::Config&)> constructor) {
52 ensure_builtins_registered();
53
54 if (is_method_registered(name)) {
55 return false;
56 }
57
58 register_method_internal(name, constructor);
59 return true;
60 }
61
62 bool ICP::is_method_registered(std::string name) {
63 ensure_builtins_registered();
64
65 return std::find(global.registered_method_names.begin(),
66 global.registered_method_names.end(), name)
67 != global.registered_method_names.end();
68 }
69
70 const std::vector<std::string>& ICP::registered_methods() {
71 ensure_builtins_registered();
72
73 return global.registered_method_names;
74 }
75
76 std::optional<std::unique_ptr<ICP>> ICP::from_method(std::string name,
77 const ICP::Config& config) {
78 ensure_builtins_registered();
79
80 auto name_it = std::find(global.registered_method_names.begin(),
81 global.registered_method_names.end(), name);
82
83 if (name_it == global.registered_method_names.end()) {
84 return {};
85 }
86
87 size_t index = name_it - global.registered_method_names.begin();
88
89 return global.registered_method_constructors[index](config);
90 }
91
92 void ICP::ensure_builtins_registered() {
93 if (builtins_registered) {
94 return;
95 }
96
97 register_method_internal("vanilla",
98 [](const ICP::Config& config) { return std::make_unique<Vanilla>(config); });
99 register_method_internal("trimmed",
100 [](const ICP::Config& config) { return std::make_unique<Trimmed>(config); });
101 register_method_internal("feature_aware",
102 [](const ICP::Config& config) { return std::make_unique<FeatureAware>(config); });
103
104 builtins_registered = true;
105 }
106
107 void ICP::register_method_internal(std::string name,
108 std::function<std::unique_ptr<ICP>(const Config&)> constructor) {
109 global.registered_method_constructors.push_back(constructor);
110 global.registered_method_names.push_back(name);
111 }
112}
Configuration for ICP instances.
Definition icp.h:80
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
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
double calculate_cost() const
Computes the cost of the current transformation.
Definition icp.cpp:35
Definition driver.h:7
Rigid-body transformation.
Definition geo.h:19