gtsam 4.1.1
gtsam
SO3.h
Go to the documentation of this file.
1/* ----------------------------------------------------------------------------
2
3 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4 * Atlanta, Georgia 30332-0415
5 * All Rights Reserved
6 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7
8 * See LICENSE for the license information
9
10 * -------------------------------------------------------------------------- */
11
21#pragma once
22
23#include <gtsam/geometry/SOn.h>
24
25#include <gtsam/base/Lie.h>
26#include <gtsam/base/Matrix.h>
27#include <gtsam/dllexport.h>
28
29#include <cmath>
30#include <vector>
31
32namespace gtsam {
33
34using SO3 = SO<3>;
35
36// Below are all declarations of SO<3> specializations.
37// They are *defined* in SO3.cpp.
38
39template <>
40GTSAM_EXPORT
41SO3 SO3::AxisAngle(const Vector3& axis, double theta);
42
43template <>
44GTSAM_EXPORT
45SO3 SO3::ClosestTo(const Matrix3& M);
46
47template <>
48GTSAM_EXPORT
49SO3 SO3::ChordalMean(const std::vector<SO3>& rotations);
50
51template <>
52GTSAM_EXPORT
53Matrix3 SO3::Hat(const Vector3& xi);
54
55template <>
56GTSAM_EXPORT
57Vector3 SO3::Vee(const Matrix3& X);
58
60template <>
61Matrix3 SO3::AdjointMap() const;
62
67template <>
68GTSAM_EXPORT
69SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H);
70
72template <>
73GTSAM_EXPORT
74Matrix3 SO3::ExpmapDerivative(const Vector3& omega);
75
80template <>
81GTSAM_EXPORT
82Vector3 SO3::Logmap(const SO3& R, ChartJacobian H);
83
85template <>
86GTSAM_EXPORT
87Matrix3 SO3::LogmapDerivative(const Vector3& omega);
88
89// Chart at origin for SO3 is *not* Cayley but actual Expmap/Logmap
90template <>
91GTSAM_EXPORT
92SO3 SO3::ChartAtOrigin::Retract(const Vector3& omega, ChartJacobian H);
93
94template <>
95GTSAM_EXPORT
96Vector3 SO3::ChartAtOrigin::Local(const SO3& R, ChartJacobian H);
97
98template <>
99GTSAM_EXPORT
100Vector9 SO3::vec(OptionalJacobian<9, 3> H) const;
101
103template <class Archive>
104void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) {
105 Matrix3& M = R.matrix_;
106 ar& boost::serialization::make_nvp("R11", M(0, 0));
107 ar& boost::serialization::make_nvp("R12", M(0, 1));
108 ar& boost::serialization::make_nvp("R13", M(0, 2));
109 ar& boost::serialization::make_nvp("R21", M(1, 0));
110 ar& boost::serialization::make_nvp("R22", M(1, 1));
111 ar& boost::serialization::make_nvp("R23", M(1, 2));
112 ar& boost::serialization::make_nvp("R31", M(2, 0));
113 ar& boost::serialization::make_nvp("R32", M(2, 1));
114 ar& boost::serialization::make_nvp("R33", M(2, 2));
115}
116
117namespace so3 {
118
123GTSAM_EXPORT Matrix3 compose(const Matrix3& M, const SO3& R,
124 OptionalJacobian<9, 9> H = boost::none);
125
127GTSAM_EXPORT Matrix99 Dcompose(const SO3& R);
128
129// Below are two functors that allow for saving computation when exponential map
130// and its derivatives are needed at the same location in so<3>. The second
131// functor also implements dedicated methods to apply dexp and/or inv(dexp).
132
134class GTSAM_EXPORT ExpmapFunctor {
135 protected:
136 const double theta2;
137 Matrix3 W, K, KK;
138 bool nearZero;
139 double theta, sin_theta, one_minus_cos; // only defined if !nearZero
140
141 void init(bool nearZeroApprox = false);
142
143 public:
145 explicit ExpmapFunctor(const Vector3& omega, bool nearZeroApprox = false);
146
148 ExpmapFunctor(const Vector3& axis, double angle, bool nearZeroApprox = false);
149
151 SO3 expmap() const;
152};
153
156 const Vector3 omega;
157 double a, b;
158 Matrix3 dexp_;
159
160 public:
162 GTSAM_EXPORT explicit DexpFunctor(const Vector3& omega, bool nearZeroApprox = false);
163
164 // NOTE(luca): Right Jacobian for Exponential map in SO(3) - equation
165 // (10.86) and following equations in G.S. Chirikjian, "Stochastic Models,
166 // Information Theory, and Lie Groups", Volume 2, 2008.
167 // expmap(omega + v) \approx expmap(omega) * expmap(dexp * v)
168 // This maps a perturbation v in the tangent space to
169 // a perturbation on the manifold Expmap(dexp * v) */
170 const Matrix3& dexp() const { return dexp_; }
171
173 GTSAM_EXPORT Vector3 applyDexp(const Vector3& v, OptionalJacobian<3, 3> H1 = boost::none,
174 OptionalJacobian<3, 3> H2 = boost::none) const;
175
177 GTSAM_EXPORT Vector3 applyInvDexp(const Vector3& v,
178 OptionalJacobian<3, 3> H1 = boost::none,
179 OptionalJacobian<3, 3> H2 = boost::none) const;
180};
181} // namespace so3
182
183/*
184 * Define the traits. internal::LieGroup provides both Lie group and Testable
185 */
186
187template <>
188struct traits<SO3> : public internal::LieGroup<SO3> {};
189
190template <>
191struct traits<const SO3> : public internal::LieGroup<SO3> {};
192
193} // end namespace gtsam
typedef and functions to augment Eigen's MatrixXd
Base class and basic functions for Lie types.
N*N matrix representation of SO(N).
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:112
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Both LieGroupTraits and Testable.
Definition: Lie.h:229
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Functor implementing Exponential map.
Definition: SO3.h:134
Functor that implements Exponential map and its derivatives.
Definition: SO3.h:155
GTSAM_EXPORT Vector3 applyDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Multiplies with dexp(), with optional derivatives.
Definition: SO3.cpp:101
GTSAM_EXPORT DexpFunctor(const Vector3 &omega, bool nearZeroApprox=false)
Constructor with element of Lie algebra so(3)
Definition: SO3.cpp:90
GTSAM_EXPORT Vector3 applyInvDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Multiplies with dexp().inverse(), with optional derivatives.
Definition: SO3.cpp:120
static SO Expmap(const TangentVector &omega, ChartJacobian H=boost::none)
Exponential map at identity - create a rotation from canonical coordinates.
Definition: SOn-inl.h:67
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H=boost::none) const
Return vectorized rotation matrix in column order.
Definition: SOn-inl.h:88
static SO ChordalMean(const std::vector< SO > &rotations)
Named constructor that finds chordal mean = argmin_R \sum sqr(|R-R_i|_F), currently only defined for ...
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
Definition: SOn-inl.h:35
static TangentVector Logmap(const SO &R, ChartJacobian H=boost::none)
Log map at identity - returns the canonical coordinates of this rotation.
Definition: SOn-inl.h:77
static SO AxisAngle(const Vector3 &axis, double theta)
Constructor from axis and angle. Only defined for SO3.
MatrixDD AdjointMap() const
Adjoint map.
Definition: SO4.cpp:159
static MatrixNN Hat(const TangentVector &xi)
Hat operator creates Lie algebra element corresponding to d-vector, where d is the dimensionality of ...
Definition: SOn-inl.h:29
static MatrixDD ExpmapDerivative(const TangentVector &omega)
Derivative of Expmap, currently only defined for SO3.
Definition: SOn-inl.h:72
static MatrixDD LogmapDerivative(const TangentVector &omega)
Derivative of Logmap, currently only defined for SO3.
Definition: SOn-inl.h:82
static SO ClosestTo(const MatrixNN &M)
Named constructor that finds SO(n) matrix closest to M in Frobenius norm, currently only defined for ...