blob: 9bd6459eb9a976805cf5eeb42389e5ef3120c489 [file] [log] [blame]
Austin Schuh3de38b02024-06-25 18:25:10 -07001// Ceres Solver - A fast non-linear least squares minimizer
2// Copyright 2023 Google Inc. All rights reserved.
3// http://ceres-solver.org/
4//
5// Redistribution and use in source and binary forms, with or without
6// modification, are permitted provided that the following conditions are met:
7//
8// * Redistributions of source code must retain the above copyright notice,
9// this list of conditions and the following disclaimer.
10// * Redistributions in binary form must reproduce the above copyright notice,
11// this list of conditions and the following disclaimer in the documentation
12// and/or other materials provided with the distribution.
13// * Neither the name of Google Inc. nor the names of its contributors may be
14// used to endorse or promote products derived from this software without
15// specific prior written permission.
16//
17// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27// POSSIBILITY OF SUCH DAMAGE.
28//
29// Author: sameeragarwal@google.com (Sameer Agarwal)
30
31#ifndef CERES_PUBLIC_MANIFOLD_H_
32#define CERES_PUBLIC_MANIFOLD_H_
33
34#include <Eigen/Core>
35#include <algorithm>
36#include <array>
37#include <memory>
38#include <utility>
39#include <vector>
40
41#include "ceres/internal/disable_warnings.h"
42#include "ceres/internal/export.h"
43#include "ceres/types.h"
44#include "glog/logging.h"
45
46namespace ceres {
47
48// In sensor fusion problems, often we have to model quantities that live in
49// spaces known as Manifolds, for example the rotation/orientation of a sensor
50// that is represented by a quaternion.
51//
52// Manifolds are spaces which locally look like Euclidean spaces. More
53// precisely, at each point on the manifold there is a linear space that is
54// tangent to the manifold. It has dimension equal to the intrinsic dimension of
55// the manifold itself, which is less than or equal to the ambient space in
56// which the manifold is embedded.
57//
58// For example, the tangent space to a point on a sphere in three dimensions is
59// the two dimensional plane that is tangent to the sphere at that point. There
60// are two reasons tangent spaces are interesting:
61//
62// 1. They are Eucliean spaces so the usual vector space operations apply there,
63// which makes numerical operations easy.
64// 2. Movement in the tangent space translate into movements along the manifold.
65// Movements perpendicular to the tangent space do not translate into
66// movements on the manifold.
67//
68// Returning to our sphere example, moving in the 2 dimensional plane
69// tangent to the sphere and projecting back onto the sphere will move you away
70// from the point you started from but moving along the normal at the same point
71// and the projecting back onto the sphere brings you back to the point.
72//
73// The Manifold interface defines two operations (and their derivatives)
74// involving the tangent space, allowing filtering and optimization to be
75// performed on said manifold:
76//
77// 1. x_plus_delta = Plus(x, delta)
78// 2. delta = Minus(x_plus_delta, x)
79//
80// "Plus" computes the result of moving along delta in the tangent space at x,
81// and then projecting back onto the manifold that x belongs to. In Differential
82// Geometry this is known as a "Retraction". It is a generalization of vector
83// addition in Euclidean spaces.
84//
85// Given two points on the manifold, "Minus" computes the change delta to x in
86// the tangent space at x, that will take it to x_plus_delta.
87//
88// Let us now consider two examples.
89//
90// The Euclidean space R^n is the simplest example of a manifold. It has
91// dimension n (and so does its tangent space) and Plus and Minus are the
92// familiar vector sum and difference operations.
93//
94// Plus(x, delta) = x + delta = y,
95// Minus(y, x) = y - x = delta.
96//
97// A more interesting case is SO(3), the special orthogonal group in three
98// dimensions - the space of 3x3 rotation matrices. SO(3) is a three dimensional
99// manifold embedded in R^9 or R^(3x3). So points on SO(3) are represented using
100// 9 dimensional vectors or 3x3 matrices, and points in its tangent spaces are
101// represented by 3 dimensional vectors.
102//
103// Defining Plus and Minus are defined in terms of the matrix Exp and Log
104// operations as follows:
105//
106// Let Exp(p, q, r) = [cos(theta) + cp^2, -sr + cpq , sq + cpr ]
107// [sr + cpq , cos(theta) + cq^2, -sp + cqr ]
108// [-sq + cpr , sp + cqr , cos(theta) + cr^2]
109//
110// where: theta = sqrt(p^2 + q^2 + r^2)
111// s = sinc(theta)
112// c = (1 - cos(theta))/theta^2
113//
114// and Log(x) = 1/(2 sinc(theta))[x_32 - x_23, x_13 - x_31, x_21 - x_12]
115//
116// where: theta = acos((Trace(x) - 1)/2)
117//
118// Then,
119//
120// Plus(x, delta) = x Exp(delta)
121// Minus(y, x) = Log(x^T y)
122//
123// For Plus and Minus to be mathematically consistent, the following identities
124// must be satisfied at all points x on the manifold:
125//
126// 1. Plus(x, 0) = x.
127// 2. For all y, Plus(x, Minus(y, x)) = y.
128// 3. For all delta, Minus(Plus(x, delta), x) = delta.
129// 4. For all delta_1, delta_2
130// |Minus(Plus(x, delta_1), Plus(x, delta_2)) <= |delta_1 - delta_2|
131//
132// Briefly:
133// (1) Ensures that the tangent space is "centered" at x, and the zero vector is
134// the identity element.
135// (2) Ensures that any y can be reached from x.
136// (3) Ensures that Plus is an injective (one-to-one) map.
137// (4) Allows us to define a metric on the manifold.
138//
139// Additionally we require that Plus and Minus be sufficiently smooth. In
140// particular they need to be differentiable everywhere on the manifold.
141//
142// For more details, please see
143//
144// "Integrating Generic Sensor Fusion Algorithms with Sound State
145// Representations through Encapsulation of Manifolds"
146// By C. Hertzberg, R. Wagner, U. Frese and L. Schroder
147// https://arxiv.org/pdf/1107.1119.pdf
148class CERES_EXPORT Manifold {
149 public:
150 virtual ~Manifold();
151
152 // Dimension of the ambient space in which the manifold is embedded.
153 virtual int AmbientSize() const = 0;
154
155 // Dimension of the manifold/tangent space.
156 virtual int TangentSize() const = 0;
157
158 // x_plus_delta = Plus(x, delta),
159 //
160 // A generalization of vector addition in Euclidean space, Plus computes the
161 // result of moving along delta in the tangent space at x, and then projecting
162 // back onto the manifold that x belongs to.
163 //
164 // x and x_plus_delta are AmbientSize() vectors.
165 // delta is a TangentSize() vector.
166 //
167 // Return value indicates if the operation was successful or not.
168 virtual bool Plus(const double* x,
169 const double* delta,
170 double* x_plus_delta) const = 0;
171
172 // Compute the derivative of Plus(x, delta) w.r.t delta at delta = 0, i.e.
173 //
174 // (D_2 Plus)(x, 0)
175 //
176 // jacobian is a row-major AmbientSize() x TangentSize() matrix.
177 //
178 // Return value indicates whether the operation was successful or not.
179 virtual bool PlusJacobian(const double* x, double* jacobian) const = 0;
180
181 // tangent_matrix = ambient_matrix * (D_2 Plus)(x, 0)
182 //
183 // ambient_matrix is a row-major num_rows x AmbientSize() matrix.
184 // tangent_matrix is a row-major num_rows x TangentSize() matrix.
185 //
186 // Return value indicates whether the operation was successful or not.
187 //
188 // This function is only used by the GradientProblemSolver, where the
189 // dimension of the parameter block can be large and it may be more efficient
190 // to compute this product directly rather than first evaluating the Jacobian
191 // into a matrix and then doing a matrix vector product.
192 //
193 // Because this is not an often used function, we provide a default
194 // implementation for convenience. If performance becomes an issue then the
195 // user should consider implementing a specialization.
196 virtual bool RightMultiplyByPlusJacobian(const double* x,
197 const int num_rows,
198 const double* ambient_matrix,
199 double* tangent_matrix) const;
200
201 // y_minus_x = Minus(y, x)
202 //
203 // Given two points on the manifold, Minus computes the change to x in the
204 // tangent space at x, that will take it to y.
205 //
206 // x and y are AmbientSize() vectors.
207 // y_minus_x is a TangentSize() vector.
208 //
209 // Return value indicates if the operation was successful or not.
210 virtual bool Minus(const double* y,
211 const double* x,
212 double* y_minus_x) const = 0;
213
214 // Compute the derivative of Minus(y, x) w.r.t y at y = x, i.e
215 //
216 // (D_1 Minus) (x, x)
217 //
218 // Jacobian is a row-major TangentSize() x AmbientSize() matrix.
219 //
220 // Return value indicates whether the operation was successful or not.
221 virtual bool MinusJacobian(const double* x, double* jacobian) const = 0;
222};
223
224// The Euclidean manifold is another name for the ordinary vector space R^size,
225// where the plus and minus operations are the usual vector addition and
226// subtraction:
227// Plus(x, delta) = x + delta
228// Minus(y, x) = y - x.
229//
230// The class works with dynamic and static ambient space dimensions. If the
231// ambient space dimensions is know at compile time use
232//
233// EuclideanManifold<3> manifold;
234//
235// If the ambient space dimensions is not known at compile time the template
236// parameter needs to be set to ceres::DYNAMIC and the actual dimension needs
237// to be provided as a constructor argument:
238//
239// EuclideanManifold<ceres::DYNAMIC> manifold(ambient_dim);
240template <int Size>
241class EuclideanManifold final : public Manifold {
242 public:
243 static_assert(Size == ceres::DYNAMIC || Size >= 0,
244 "The size of the manifold needs to be non-negative.");
245 static_assert(ceres::DYNAMIC == Eigen::Dynamic,
246 "ceres::DYNAMIC needs to be the same as Eigen::Dynamic.");
247
248 EuclideanManifold() : size_{Size} {
249 static_assert(
250 Size != ceres::DYNAMIC,
251 "The size is set to dynamic. Please call the constructor with a size.");
252 }
253
254 explicit EuclideanManifold(int size) : size_(size) {
255 if (Size != ceres::DYNAMIC) {
256 CHECK_EQ(Size, size)
257 << "Specified size by template parameter differs from the supplied "
258 "one.";
259 } else {
260 CHECK_GE(size_, 0)
261 << "The size of the manifold needs to be non-negative.";
262 }
263 }
264
265 int AmbientSize() const override { return size_; }
266 int TangentSize() const override { return size_; }
267
268 bool Plus(const double* x_ptr,
269 const double* delta_ptr,
270 double* x_plus_delta_ptr) const override {
271 Eigen::Map<const AmbientVector> x(x_ptr, size_);
272 Eigen::Map<const AmbientVector> delta(delta_ptr, size_);
273 Eigen::Map<AmbientVector> x_plus_delta(x_plus_delta_ptr, size_);
274 x_plus_delta = x + delta;
275 return true;
276 }
277
278 bool PlusJacobian(const double* x_ptr, double* jacobian_ptr) const override {
279 Eigen::Map<MatrixJacobian> jacobian(jacobian_ptr, size_, size_);
280 jacobian.setIdentity();
281 return true;
282 }
283
284 bool RightMultiplyByPlusJacobian(const double* x,
285 const int num_rows,
286 const double* ambient_matrix,
287 double* tangent_matrix) const override {
288 std::copy_n(ambient_matrix, num_rows * size_, tangent_matrix);
289 return true;
290 }
291
292 bool Minus(const double* y_ptr,
293 const double* x_ptr,
294 double* y_minus_x_ptr) const override {
295 Eigen::Map<const AmbientVector> x(x_ptr, size_);
296 Eigen::Map<const AmbientVector> y(y_ptr, size_);
297 Eigen::Map<AmbientVector> y_minus_x(y_minus_x_ptr, size_);
298 y_minus_x = y - x;
299 return true;
300 }
301
302 bool MinusJacobian(const double* x_ptr, double* jacobian_ptr) const override {
303 Eigen::Map<MatrixJacobian> jacobian(jacobian_ptr, size_, size_);
304 jacobian.setIdentity();
305 return true;
306 }
307
308 private:
309 static constexpr bool IsDynamic = (Size == ceres::DYNAMIC);
310 using AmbientVector = Eigen::Matrix<double, Size, 1>;
311 using MatrixJacobian = Eigen::Matrix<double, Size, Size, Eigen::RowMajor>;
312
313 int size_{};
314};
315
316// Hold a subset of the parameters inside a parameter block constant.
317class CERES_EXPORT SubsetManifold final : public Manifold {
318 public:
319 SubsetManifold(int size, const std::vector<int>& constant_parameters);
320 int AmbientSize() const override;
321 int TangentSize() const override;
322
323 bool Plus(const double* x,
324 const double* delta,
325 double* x_plus_delta) const override;
326 bool PlusJacobian(const double* x, double* jacobian) const override;
327 bool RightMultiplyByPlusJacobian(const double* x,
328 const int num_rows,
329 const double* ambient_matrix,
330 double* tangent_matrix) const override;
331 bool Minus(const double* y,
332 const double* x,
333 double* y_minus_x) const override;
334 bool MinusJacobian(const double* x, double* jacobian) const override;
335
336 private:
337 const int tangent_size_ = 0;
338 std::vector<bool> constancy_mask_;
339};
340
341// Implements the manifold for a Hamilton quaternion as defined in
342// https://en.wikipedia.org/wiki/Quaternion. Quaternions are represented as
343// unit norm 4-vectors, i.e.
344//
345// q = [q0; q1; q2; q3], |q| = 1
346//
347// is the ambient space representation.
348//
349// q0 scalar part.
350// q1 coefficient of i.
351// q2 coefficient of j.
352// q3 coefficient of k.
353//
354// where: i*i = j*j = k*k = -1 and i*j = k, j*k = i, k*i = j.
355//
356// The tangent space is R^3, which relates to the ambient space through the
357// Plus and Minus operations defined as:
358//
359// Plus(x, delta) = [cos(|delta|); sin(|delta|) * delta / |delta|] * x
360// Minus(y, x) = to_delta(y * x^{-1})
361//
362// where "*" is the quaternion product and because q is a unit quaternion
363// (|q|=1), q^-1 = [q0; -q1; -q2; -q3]
364//
365// and to_delta( [q0; u_{3x1}] ) = u / |u| * atan2(|u|, q0)
366class CERES_EXPORT QuaternionManifold final : public Manifold {
367 public:
368 int AmbientSize() const override { return 4; }
369 int TangentSize() const override { return 3; }
370
371 bool Plus(const double* x,
372 const double* delta,
373 double* x_plus_delta) const override;
374 bool PlusJacobian(const double* x, double* jacobian) const override;
375 bool Minus(const double* y,
376 const double* x,
377 double* y_minus_x) const override;
378 bool MinusJacobian(const double* x, double* jacobian) const override;
379};
380
381// Implements the quaternion manifold for Eigen's representation of the
382// Hamilton quaternion. Geometrically it is exactly the same as the
383// QuaternionManifold defined above. However, Eigen uses a different internal
384// memory layout for the elements of the quaternion than what is commonly
385// used. It stores the quaternion in memory as [q1, q2, q3, q0] or
386// [x, y, z, w] where the real (scalar) part is last.
387//
388// Since Ceres operates on parameter blocks which are raw double pointers this
389// difference is important and requires a different manifold.
390class CERES_EXPORT EigenQuaternionManifold final : public Manifold {
391 public:
392 int AmbientSize() const override { return 4; }
393 int TangentSize() const override { return 3; }
394
395 bool Plus(const double* x,
396 const double* delta,
397 double* x_plus_delta) const override;
398 bool PlusJacobian(const double* x, double* jacobian) const override;
399 bool Minus(const double* y,
400 const double* x,
401 double* y_minus_x) const override;
402 bool MinusJacobian(const double* x, double* jacobian) const override;
403};
404
405} // namespace ceres
406
407// clang-format off
408#include "ceres/internal/reenable_warnings.h"
409// clang-format on
410
411#endif // CERES_PUBLIC_MANIFOLD_H_