gtsam 4.1.1
gtsam
Lie.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
24#pragma once
25
26#include <gtsam/base/Manifold.h>
27#include <gtsam/base/Group.h>
28
29namespace gtsam {
30
36template <class Class, int N>
37struct LieGroup {
38
39 enum { dimension = N };
41 typedef Eigen::Matrix<double, N, N> Jacobian;
42 typedef Eigen::Matrix<double, N, 1> TangentVector;
43
44 const Class & derived() const {
45 return static_cast<const Class&>(*this);
46 }
47
48 Class compose(const Class& g) const {
49 return derived() * g;
50 }
51
52 Class between(const Class& g) const {
53 return derived().inverse() * g;
54 }
55
56 Class compose(const Class& g, ChartJacobian H1,
57 ChartJacobian H2 = boost::none) const {
58 if (H1) *H1 = g.inverse().AdjointMap();
59 if (H2) *H2 = Eigen::Matrix<double, N, N>::Identity();
60 return derived() * g;
61 }
62
63 Class between(const Class& g, ChartJacobian H1,
64 ChartJacobian H2 = boost::none) const {
65 Class result = derived().inverse() * g;
66 if (H1) *H1 = - result.inverse().AdjointMap();
67 if (H2) *H2 = Eigen::Matrix<double, N, N>::Identity();
68 return result;
69 }
70
71 Class inverse(ChartJacobian H) const {
72 if (H) *H = - derived().AdjointMap();
73 return derived().inverse();
74 }
75
78 Class expmap(const TangentVector& v) const {
79 return compose(Class::Expmap(v));
80 }
81
84 TangentVector logmap(const Class& g) const {
85 return Class::Logmap(between(g));
86 }
87
89 Class expmap(const TangentVector& v, //
90 ChartJacobian H1, ChartJacobian H2 = boost::none) const {
91 Jacobian D_g_v;
92 Class g = Class::Expmap(v,H2 ? &D_g_v : 0);
93 Class h = compose(g); // derivatives inlined below
94 if (H1) *H1 = g.inverse().AdjointMap();
95 if (H2) *H2 = D_g_v;
96 return h;
97 }
98
100 TangentVector logmap(const Class& g, //
101 ChartJacobian H1, ChartJacobian H2 = boost::none) const {
102 Class h = between(g); // derivatives inlined below
103 Jacobian D_v_h;
104 TangentVector v = Class::Logmap(h, (H1 || H2) ? &D_v_h : 0);
105 if (H1) *H1 = - D_v_h * h.inverse().AdjointMap();
106 if (H2) *H2 = D_v_h;
107 return v;
108 }
109
111 static Class Retract(const TangentVector& v) {
112 return Class::ChartAtOrigin::Retract(v);
113 }
114
116 static TangentVector LocalCoordinates(const Class& g) {
117 return Class::ChartAtOrigin::Local(g);
118 }
119
121 static Class Retract(const TangentVector& v, ChartJacobian H) {
122 return Class::ChartAtOrigin::Retract(v,H);
123 }
124
126 static TangentVector LocalCoordinates(const Class& g, ChartJacobian H) {
127 return Class::ChartAtOrigin::Local(g,H);
128 }
129
131 Class retract(const TangentVector& v) const {
132 return compose(Class::ChartAtOrigin::Retract(v));
133 }
134
136 TangentVector localCoordinates(const Class& g) const {
137 return Class::ChartAtOrigin::Local(between(g));
138 }
139
141 Class retract(const TangentVector& v, //
142 ChartJacobian H1, ChartJacobian H2 = boost::none) const {
143 Jacobian D_g_v;
144 Class g = Class::ChartAtOrigin::Retract(v, H2 ? &D_g_v : 0);
145 Class h = compose(g); // derivatives inlined below
146 if (H1) *H1 = g.inverse().AdjointMap();
147 if (H2) *H2 = D_g_v;
148 return h;
149 }
150
152 TangentVector localCoordinates(const Class& g, //
153 ChartJacobian H1, ChartJacobian H2 = boost::none) const {
154 Class h = between(g); // derivatives inlined below
155 Jacobian D_v_h;
156 TangentVector v = Class::ChartAtOrigin::Local(h, (H1 || H2) ? &D_v_h : 0);
157 if (H1) *H1 = - D_v_h * h.inverse().AdjointMap();
158 if (H2) *H2 = D_v_h;
159 return v;
160 }
161};
162
164struct lie_group_tag: public manifold_tag, public group_tag {};
165
166namespace internal {
167
173template<class Class>
174struct LieGroupTraits: GetDimensionImpl<Class, Class::dimension> {
176
180 static Class Identity() { return Class::identity();}
182
185 typedef Class ManifoldType;
186 enum { dimension = Class::dimension };
187 typedef Eigen::Matrix<double, dimension, 1> TangentVector;
189
190 static TangentVector Local(const Class& origin, const Class& other,
191 ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) {
192 return origin.localCoordinates(other, Horigin, Hother);
193 }
194
195 static Class Retract(const Class& origin, const TangentVector& v,
196 ChartJacobian Horigin = boost::none, ChartJacobian Hv = boost::none) {
197 return origin.retract(v, Horigin, Hv);
198 }
200
203 static TangentVector Logmap(const Class& m, ChartJacobian Hm = boost::none) {
204 return Class::Logmap(m, Hm);
205 }
206
207 static Class Expmap(const TangentVector& v, ChartJacobian Hv = boost::none) {
208 return Class::Expmap(v, Hv);
209 }
210
211 static Class Compose(const Class& m1, const Class& m2, //
212 ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
213 return m1.compose(m2, H1, H2);
214 }
215
216 static Class Between(const Class& m1, const Class& m2, //
217 ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
218 return m1.between(m2, H1, H2);
219 }
220
221 static Class Inverse(const Class& m, //
222 ChartJacobian H = boost::none) {
223 return m.inverse(H);
224 }
226};
227
229template<class Class> struct LieGroup: LieGroupTraits<Class>, Testable<Class> {};
230
231} // \ namepsace internal
232
239template<class Class>
240inline Class between_default(const Class& l1, const Class& l2) {
241 return l1.inverse().compose(l2);
242}
243
245template<class Class>
246inline Vector logmap_default(const Class& l0, const Class& lp) {
247 return Class::Logmap(l0.between(lp));
248}
249
251template<class Class>
252inline Class expmap_default(const Class& t, const Vector& d) {
253 return t.compose(Class::Expmap(d));
254}
255
259template<typename T>
260class IsLieGroup: public IsGroup<T>, public IsManifold<T> {
261public:
262 typedef typename traits<T>::structure_category structure_category_tag;
263 typedef typename traits<T>::ManifoldType ManifoldType;
264 typedef typename traits<T>::TangentVector TangentVector;
265 typedef typename traits<T>::ChartJacobian ChartJacobian;
266
267 BOOST_CONCEPT_USAGE(IsLieGroup) {
268 BOOST_STATIC_ASSERT_MSG(
269 (boost::is_base_of<lie_group_tag, structure_category_tag>::value),
270 "This type's trait does not assert it is a Lie group (or derived)");
271
272 // group opertations with Jacobians
273 g = traits<T>::Compose(g, h, Hg, Hh);
274 g = traits<T>::Between(g, h, Hg, Hh);
275 g = traits<T>::Inverse(g, Hg);
276 // log and exp map without Jacobians
277 g = traits<T>::Expmap(v);
278 v = traits<T>::Logmap(g);
279 // log and exponential map with Jacobians
280 g = traits<T>::Expmap(v, Hg);
281 v = traits<T>::Logmap(g, Hg);
282 }
283private:
284 T g, h;
285 TangentVector v;
286 ChartJacobian Hg, Hh;
287};
288
297template<class T>
298T BCH(const T& X, const T& Y) {
299 static const double _2 = 1. / 2., _12 = 1. / 12., _24 = 1. / 24.;
300 T X_Y = bracket(X, Y);
301 return T(X + Y + _2 * X_Y + _12 * bracket(X - Y, X_Y) - _24 * bracket(Y, bracket(X, X_Y)));
302}
303
308template <class T> Matrix wedge(const Vector& x);
309
316template <class T>
317T expm(const Vector& x, int K=7) {
318 Matrix xhat = wedge<T>(x);
319 return T(expm(xhat,K));
320}
321
326template <typename T>
327T interpolate(const T& X, const T& Y, double t,
328 typename MakeOptionalJacobian<T, T>::type Hx = boost::none,
329 typename MakeOptionalJacobian<T, T>::type Hy = boost::none) {
330 if (Hx || Hy) {
331 typename MakeJacobian<T, T>::type between_H_x, log_H, exp_H, compose_H_x;
332 const T between =
333 traits<T>::Between(X, Y, between_H_x); // between_H_y = identity
334 typename traits<T>::TangentVector delta = traits<T>::Logmap(between, log_H);
335 const T Delta = traits<T>::Expmap(t * delta, exp_H);
336 const T result = traits<T>::Compose(
337 X, Delta, compose_H_x); // compose_H_xinv_y = identity
338
339 if (Hx) *Hx = compose_H_x + t * exp_H * log_H * between_H_x;
340 if (Hy) *Hy = t * exp_H * log_H;
341 return result;
342 }
343 return traits<T>::Compose(
345}
346
351template<class T>
353{
354private:
355 typename T::Jacobian adjointMap_;
356public:
357 explicit TransformCovariance(const T &X) : adjointMap_{X.AdjointMap()} {}
358 typename T::Jacobian operator()(const typename T::Jacobian &covariance)
359 { return adjointMap_ * covariance * adjointMap_.transpose(); }
360};
361
362} // namespace gtsam
363
372#define GTSAM_CONCEPT_LIE_INST(T) template class gtsam::IsLieGroup<T>;
373#define GTSAM_CONCEPT_LIE_TYPE(T) using _gtsam_IsLieGroup_##T = gtsam::IsLieGroup<T>;
Concept check class for variable types with Group properties.
Base class and basic functions for Manifold types.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
T expm(const Vector &x, int K=7)
Exponential map given exponential coordinates class T needs a wedge<> function and a constructor from...
Definition: Lie.h:317
Vector logmap_default(const Class &l0, const Class &lp)
Log map centered at l0, s.t.
Definition: Lie.h:246
Class between_default(const Class &l1, const Class &l2)
These core global functions can be specialized by new Lie types for better performance.
Definition: Lie.h:240
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx=boost::none, typename MakeOptionalJacobian< T, T >::type Hy=boost::none)
Linear interpolation between X and Y by coefficient t.
Definition: Lie.h:327
T BCH(const T &X, const T &Y)
Three term approximation of the Baker-Campbell-Hausdorff formula In non-commutative Lie groups,...
Definition: Lie.h:298
Class expmap_default(const Class &t, const Vector &d)
Exponential map centered at l0, s.t.
Definition: Lie.h:252
Matrix wedge(const Vector &x)
Declaration of wedge (see Murray94book) used to convert from n exponential coordinates to n*n element...
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
tag to assert a type is a group
Definition: Group.h:34
Group operator syntax flavors.
Definition: Group.h:37
Group Concept.
Definition: Group.h:46
A CRTP helper class that implements Lie group methods Prerequisites: methods operator*,...
Definition: Lie.h:37
static Class Retract(const TangentVector &v, ChartJacobian H)
Retract at origin with optional derivative.
Definition: Lie.h:121
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:136
Class expmap(const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
expmap with optional derivatives
Definition: Lie.h:89
TangentVector localCoordinates(const Class &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
localCoordinates with optional derivatives
Definition: Lie.h:152
TangentVector logmap(const Class &g) const
logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g
Definition: Lie.h:84
TangentVector logmap(const Class &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
logmap with optional derivatives
Definition: Lie.h:100
static TangentVector LocalCoordinates(const Class &g)
LocalCoordinates at origin: possible in Lie group because it has an identity.
Definition: Lie.h:116
Class retract(const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
retract with optional derivatives
Definition: Lie.h:141
static TangentVector LocalCoordinates(const Class &g, ChartJacobian H)
LocalCoordinates at origin with optional derivative.
Definition: Lie.h:126
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:131
Class expmap(const TangentVector &v) const
expmap as required by manifold concept Applies exponential map to v and composes with *this
Definition: Lie.h:78
static Class Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
Definition: Lie.h:111
tag to assert a type is a Lie group
Definition: Lie.h:164
A helper class that implements the traits interface for GTSAM lie groups.
Definition: Lie.h:174
Both LieGroupTraits and Testable.
Definition: Lie.h:229
Lie Group Concept.
Definition: Lie.h:260
Functor for transforming covariance of T.
Definition: Lie.h:353
tag to assert a type is a manifold
Definition: Manifold.h:33
Extra manifold traits for fixed-dimension types.
Definition: Manifold.h:75
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151