iterative closest points
CEV ICP algorithm library
Loading...
Searching...
No Matches
vanilla.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 <cassert>
7#include <cstdlib>
8#include <Eigen/Core>
9#include <Eigen/SVD>
10#include <Eigen/Dense>
11
12#include "icp/impl/vanilla.h"
13
14/* #name Vanilla */
15/* #register vanilla */
16
17/* #desc The vanilla algorithm for ICP will match the point-cloud centers
18exactly and then iterate until an optimal rotation has been found. */
19
20namespace icp {
21 Vanilla::Vanilla([[maybe_unused]] const Config& config): ICP() {}
24
26 a_current.resize(a.size());
27 b_cm = get_centroid(b);
28
29 compute_matches();
30 }
31
33 const size_t n = a.size();
34
35 for (size_t i = 0; i < n; i++) {
36 a_current[i] = transform.apply_to(a[i]);
37 }
38
39 // can optimize by just transforming prev centroid if necessary
40 auto a_current_cm = get_centroid(a_current);
41
42 /*
43 #step
44 Matching Step: match closest points.
45
46 Sources:
47 https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=4767965
48 https://arxiv.org/pdf/2206.06435.pdf
49 https://web.archive.org/web/20220615080318/https://www.cs.technion.ac.il/~cs236329/tutorials/ICP.pdf
50 https://en.wikipedia.org/wiki/Iterative_closest_point
51 https://courses.cs.duke.edu/spring07/cps296.2/scribe_notes/lecture24.pdf
52 -> use k-d tree
53 */
54 compute_matches();
55
56 /*
57 #step
58 SVD
59
60 We compute the SVD of this magical matrix. A proof that this yields the optimal
61 transform R is in the source below.
62
63 Sources:
64 https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=4767965
65 */
66 Matrix N = Matrix::Zero();
67 for (size_t i = 0; i < n; i++) {
68 N += (a_current[i] - a_current_cm) * (b[matches[i].pair] - b_cm).transpose();
69 }
70 auto svd = N.jacobiSvd(Eigen::ComputeFullU | Eigen::ComputeFullV);
71 const Matrix U = svd.matrixU();
72 Matrix V = svd.matrixV();
73 Matrix R = V * U.transpose();
74
75 /*
76 #step
77 Reflection Handling
78
79 SVD may return a reflection instead of a rotation if it's equally good or better.
80 This is exceedingly rare with real data but may happen in very high noise
81 environment with sparse point cloud.
82
83 In the 2D case, we can always recover a reasonable rotation by negating the last
84 column of V. I do not know if this is the optimal rotation among rotations, but
85 we can probably get an answer to that question with more effort.
86
87 Sources:
88 https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=4767965
89 */
90 if (R.determinant() < 0) {
91 V = V * Eigen::DiagonalMatrix<double, 2>(1, -1);
92 R = V * U.transpose();
93 }
94
96
97 /*
98 #step
99 Transformation Step: determine optimal transformation.
100
101 The translation vector is determined by the displacement between
102 the centroids of both point clouds. The rotation matrix is
103 calculated via singular value decomposition.
104
105 Sources:
106 https://ieeexplore.ieee.org/stamp/stamp.jsp?tp=&arnumber=4767965
107 https://courses.cs.duke.edu/spring07/cps296.2/scribe_notes/lecture24.pdf
108 */
109 transform.translation += b_cm - R * a_current_cm;
110 }
111}
112
113void icp::Vanilla::compute_matches() {
114 const size_t n = a.size();
115 const size_t m = b.size();
116
117 for (size_t i = 0; i < n; i++) {
118 matches[i].cost = std::numeric_limits<double>::infinity();
119 for (size_t j = 0; j < m; j++) {
120 // Point-to-point matching
121 double dist_ij = (b[j] - a_current[i]).squaredNorm();
122
123 if (dist_ij < matches[i].cost) {
124 matches[i].cost = dist_ij;
125 matches[i].pair = j;
126 }
127 }
128 }
129}
Configuration for ICP instances.
Definition icp.h:80
Interface for iterative closest points.
Definition icp.h:48
RBTransform transform
The current point cloud transformation that is being optimized.
Definition icp.h:58
std::vector< Vector > a
The source point cloud.
Definition icp.h:61
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 iterate() override
Perform one iteration of ICP for the point clouds a and b provided with ICP::begin.
Definition vanilla.cpp:32
void setup() override
Per-method setup code.
Definition vanilla.cpp:25
Definition driver.h:7
Eigen::Matrix2d Matrix
Definition geo.h:16
Vector get_centroid(const std::vector< Vector > &points)
Definition geo.cpp:10
Matrix rotation
Definition geo.h:21
Vector apply_to(Vector v) const
Definition geo.h:31
Vector translation
Definition geo.h:20