gtsam  4.0.0
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 
23 #pragma once
24 
25 #include <gtsam/base/Manifold.h>
26 #include <gtsam/base/Group.h>
27 
28 namespace gtsam {
29 
35 template <class Class, int N>
36 struct LieGroup {
37 
38  BOOST_STATIC_ASSERT_MSG(N != Eigen::Dynamic,
39  "LieGroup not yet specialized for dynamically sized types.");
40 
41  enum { dimension = N };
43  typedef Eigen::Matrix<double, N, N> Jacobian;
44  typedef Eigen::Matrix<double, N, 1> TangentVector;
45 
46  const Class & derived() const {
47  return static_cast<const Class&>(*this);
48  }
49 
50  Class compose(const Class& g) const {
51  return derived() * g;
52  }
53 
54  Class between(const Class& g) const {
55  return derived().inverse() * g;
56  }
57 
58  Class compose(const Class& g, ChartJacobian H1,
59  ChartJacobian H2 = boost::none) const {
60  if (H1) *H1 = g.inverse().AdjointMap();
61  if (H2) *H2 = Eigen::Matrix<double, N, N>::Identity();
62  return derived() * g;
63  }
64 
65  Class between(const Class& g, ChartJacobian H1,
66  ChartJacobian H2 = boost::none) const {
67  Class result = derived().inverse() * g;
68  if (H1) *H1 = - result.inverse().AdjointMap();
69  if (H2) *H2 = Eigen::Matrix<double, N, N>::Identity();
70  return result;
71  }
72 
73  Class inverse(ChartJacobian H) const {
74  if (H) *H = - derived().AdjointMap();
75  return derived().inverse();
76  }
77 
80  Class expmap(const TangentVector& v) const {
81  return compose(Class::Expmap(v));
82  }
83 
86  TangentVector logmap(const Class& g) const {
87  return Class::Logmap(between(g));
88  }
89 
91  Class expmap(const TangentVector& v, //
92  ChartJacobian H1, ChartJacobian H2 = boost::none) const {
93  Jacobian D_g_v;
94  Class g = Class::Expmap(v,H2 ? &D_g_v : 0);
95  Class h = compose(g); // derivatives inlined below
96  if (H1) *H1 = g.inverse().AdjointMap();
97  if (H2) *H2 = D_g_v;
98  return h;
99  }
100 
102  TangentVector logmap(const Class& g, //
103  ChartJacobian H1, ChartJacobian H2 = boost::none) const {
104  Class h = between(g); // derivatives inlined below
105  Jacobian D_v_h;
106  TangentVector v = Class::Logmap(h, (H1 || H2) ? &D_v_h : 0);
107  if (H1) *H1 = - D_v_h * h.inverse().AdjointMap();
108  if (H2) *H2 = D_v_h;
109  return v;
110  }
111 
113  static Class Retract(const TangentVector& v) {
114  return Class::ChartAtOrigin::Retract(v);
115  }
116 
118  static TangentVector LocalCoordinates(const Class& g) {
119  return Class::ChartAtOrigin::Local(g);
120  }
121 
123  static Class Retract(const TangentVector& v, ChartJacobian H) {
124  return Class::ChartAtOrigin::Retract(v,H);
125  }
126 
128  static TangentVector LocalCoordinates(const Class& g, ChartJacobian H) {
129  return Class::ChartAtOrigin::Local(g,H);
130  }
131 
133  Class retract(const TangentVector& v) const {
134  return compose(Class::ChartAtOrigin::Retract(v));
135  }
136 
138  TangentVector localCoordinates(const Class& g) const {
139  return Class::ChartAtOrigin::Local(between(g));
140  }
141 
143  Class retract(const TangentVector& v, //
144  ChartJacobian H1, ChartJacobian H2 = boost::none) const {
145  Jacobian D_g_v;
146  Class g = Class::ChartAtOrigin::Retract(v, H2 ? &D_g_v : 0);
147  Class h = compose(g); // derivatives inlined below
148  if (H1) *H1 = g.inverse().AdjointMap();
149  if (H2) *H2 = D_g_v;
150  return h;
151  }
152 
154  TangentVector localCoordinates(const Class& g, //
155  ChartJacobian H1, ChartJacobian H2 = boost::none) const {
156  Class h = between(g); // derivatives inlined below
157  Jacobian D_v_h;
158  TangentVector v = Class::ChartAtOrigin::Local(h, (H1 || H2) ? &D_v_h : 0);
159  if (H1) *H1 = - D_v_h * h.inverse().AdjointMap();
160  if (H2) *H2 = D_v_h;
161  return v;
162  }
163 
164 };
165 
167 struct lie_group_tag: public manifold_tag, public group_tag {};
168 
169 namespace internal {
170 
176 template<class Class>
179 
183  static Class Identity() { return Class::identity();}
185 
188  typedef Class ManifoldType;
189  enum { dimension = Class::dimension };
190  typedef Eigen::Matrix<double, dimension, 1> TangentVector;
192 
193  BOOST_STATIC_ASSERT_MSG(dimension != Eigen::Dynamic,
194  "LieGroupTraits not yet specialized for dynamically sized types.");
195 
196  static int GetDimension(const Class&) {return dimension;}
197 
198  static TangentVector Local(const Class& origin, const Class& other,
199  ChartJacobian Horigin = boost::none, ChartJacobian Hother = boost::none) {
200  return origin.localCoordinates(other, Horigin, Hother);
201  }
202 
203  static Class Retract(const Class& origin, const TangentVector& v,
204  ChartJacobian Horigin = boost::none, ChartJacobian Hv = boost::none) {
205  return origin.retract(v, Horigin, Hv);
206  }
208 
211  static TangentVector Logmap(const Class& m, ChartJacobian Hm = boost::none) {
212  return Class::Logmap(m, Hm);
213  }
214 
215  static Class Expmap(const TangentVector& v, ChartJacobian Hv = boost::none) {
216  return Class::Expmap(v, Hv);
217  }
218 
219  static Class Compose(const Class& m1, const Class& m2, //
220  ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
221  return m1.compose(m2, H1, H2);
222  }
223 
224  static Class Between(const Class& m1, const Class& m2, //
225  ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
226  return m1.between(m2, H1, H2);
227  }
228 
229  static Class Inverse(const Class& m, //
230  ChartJacobian H = boost::none) {
231  return m.inverse(H);
232  }
234 };
235 
237 template<class Class> struct LieGroup: LieGroupTraits<Class>, Testable<Class> {};
238 
239 } // \ namepsace internal
240 
247 template<class Class>
248 inline Class between_default(const Class& l1, const Class& l2) {
249  return l1.inverse().compose(l2);
250 }
251 
253 template<class Class>
254 inline Vector logmap_default(const Class& l0, const Class& lp) {
255  return Class::Logmap(l0.between(lp));
256 }
257 
259 template<class Class>
260 inline Class expmap_default(const Class& t, const Vector& d) {
261  return t.compose(Class::Expmap(d));
262 }
263 
267 template<typename T>
268 class IsLieGroup: public IsGroup<T>, public IsManifold<T> {
269 public:
270  typedef typename traits<T>::structure_category structure_category_tag;
271  typedef typename traits<T>::ManifoldType ManifoldType;
272  typedef typename traits<T>::TangentVector TangentVector;
273  typedef typename traits<T>::ChartJacobian ChartJacobian;
274 
275  BOOST_CONCEPT_USAGE(IsLieGroup) {
276  BOOST_STATIC_ASSERT_MSG(
277  (boost::is_base_of<lie_group_tag, structure_category_tag>::value),
278  "This type's trait does not assert it is a Lie group (or derived)");
279 
280  // group opertations with Jacobians
281  g = traits<T>::Compose(g, h, Hg, Hh);
282  g = traits<T>::Between(g, h, Hg, Hh);
283  g = traits<T>::Inverse(g, Hg);
284  // log and exp map without Jacobians
285  g = traits<T>::Expmap(v);
286  v = traits<T>::Logmap(g);
287  // log and exponential map with Jacobians
288  g = traits<T>::Expmap(v, Hg);
289  v = traits<T>::Logmap(g, Hg);
290  }
291 private:
292  T g, h;
293  TangentVector v;
294  ChartJacobian Hg, Hh;
295 };
296 
304 template<class T>
306 T BCH(const T& X, const T& Y) {
307  static const double _2 = 1. / 2., _12 = 1. / 12., _24 = 1. / 24.;
308  T X_Y = bracket(X, Y);
309  return T(X + Y + _2 * X_Y + _12 * bracket(X - Y, X_Y) - _24 * bracket(Y, bracket(X, X_Y)));
310 }
311 
316 template <class T> Matrix wedge(const Vector& x);
317 
324 template <class T>
325 T expm(const Vector& x, int K=7) {
326  Matrix xhat = wedge<T>(x);
327  return T(expm(xhat,K));
328 }
329 
333 template <typename T>
334 T interpolate(const T& X, const T& Y, double t) {
335  assert(t >= 0 && t <= 1);
337 }
338 
339 } // namespace gtsam
340 
349 #define GTSAM_CONCEPT_LIE_INST(T) template class gtsam::IsLieGroup<T>;
350 #define GTSAM_CONCEPT_LIE_TYPE(T) typedef gtsam::IsLieGroup<T> _gtsam_IsLieGroup_##T;
Matrix wedge(const Vector &x)
Declaration of wedge (see Murray94book) used to convert from n exponential coordinates to n*n element...
Group operator syntax flavors.
Definition: Group.h:37
Base class and basic functions for Manifold types.
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:86
static Class Retract(const TangentVector &v, ChartJacobian H)
Retract at origin with optional derivative.
Definition: Lie.h:123
Class retract(const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
retract with optional derivatives
Definition: Lie.h:143
TangentVector localCoordinates(const Class &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
localCoordinates with optional derivatives
Definition: Lie.h:154
static TangentVector LocalCoordinates(const Class &g, ChartJacobian H)
LocalCoordinates at origin with optional derivative.
Definition: Lie.h:128
Both LieGroupTraits and Testable.
Definition: Lie.h:237
Concept check class for variable types with Group properties.
T interpolate(const T &X, const T &Y, double t)
Linear interpolation between X and Y by coefficient t in [0, 1].
Definition: Lie.h:334
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
Group Concept.
Definition: Group.h:46
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
tag to assert a type is a group
Definition: Group.h:34
Vector logmap_default(const Class &l0, const Class &lp)
Log map centered at l0, s.t.
Definition: Lie.h:254
A CRTP helper class that implements Lie group methods Prerequisites: methods operator*,...
Definition: Lie.h:36
static Class Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
Definition: Lie.h:113
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:133
tag to assert a type is a manifold
Definition: Manifold.h:33
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
A helper class that implements the traits interface for GTSAM lie groups.
Definition: Lie.h:177
TangentVector logmap(const Class &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
logmap with optional derivatives
Definition: Lie.h:102
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:306
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:248
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:325
static TangentVector LocalCoordinates(const Class &g)
LocalCoordinates at origin: possible in Lie group because it has an identity.
Definition: Lie.h:118
Lie Group Concept.
Definition: Lie.h:268
tag to assert a type is a Lie group
Definition: Lie.h:167
Class expmap(const TangentVector &v) const
expmap as required by manifold concept Applies exponential map to v and composes with *this
Definition: Lie.h:80
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Class expmap(const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
expmap with optional derivatives
Definition: Lie.h:91
Class expmap_default(const Class &t, const Vector &d)
Exponential map centered at l0, s.t.
Definition: Lie.h:260
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
Definition: Lie.h:138