GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
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 
29 namespace gtsam {
30 
36 template <class Class, int N>
37 struct 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 = {}) 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 = {}) 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 = {}) 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 = {}) 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 = {}) 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 = {}) 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 
164 struct lie_group_tag: public manifold_tag, public group_tag {};
165 
166 namespace internal {
167 
173 template<class Class>
174 struct 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;
188  typedef OptionalJacobian<dimension, dimension> ChartJacobian;
189 
190  static TangentVector Local(const Class& origin, const Class& other,
191  ChartJacobian Horigin = {}, ChartJacobian Hother = {}) {
192  return origin.localCoordinates(other, Horigin, Hother);
193  }
194 
195  static Class Retract(const Class& origin, const TangentVector& v,
196  ChartJacobian Horigin = {}, ChartJacobian Hv = {}) {
197  return origin.retract(v, Horigin, Hv);
198  }
200 
203  static TangentVector Logmap(const Class& m, ChartJacobian Hm = {}) {
204  return Class::Logmap(m, Hm);
205  }
206 
207  static Class Expmap(const TangentVector& v, ChartJacobian Hv = {}) {
208  return Class::Expmap(v, Hv);
209  }
210 
211  static Class Compose(const Class& m1, const Class& m2, //
212  ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
213  return m1.compose(m2, H1, H2);
214  }
215 
216  static Class Between(const Class& m1, const Class& m2, //
217  ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
218  return m1.between(m2, H1, H2);
219  }
220 
221  static Class Inverse(const Class& m, //
222  ChartJacobian H = {}) {
223  return m.inverse(H);
224  }
226 };
227 
229 template<class Class> struct LieGroup: LieGroupTraits<Class>, Testable<Class> {};
230 
231 } // \ namepsace internal
232 
239 template<class Class>
240 inline Class between_default(const Class& l1, const Class& l2) {
241  return l1.inverse().compose(l2);
242 }
243 
245 template<class Class>
246 inline Vector logmap_default(const Class& l0, const Class& lp) {
247  return Class::Logmap(l0.between(lp));
248 }
249 
251 template<class Class>
252 inline Class expmap_default(const Class& t, const Vector& d) {
253  return t.compose(Class::Expmap(d));
254 }
255 
259 template<typename T>
260 class IsLieGroup: public IsGroup<T>, public IsManifold<T> {
261 public:
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  static_assert(
269  (std::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  }
283 private:
284  T g, h;
285  TangentVector v;
286  ChartJacobian Hg, Hh;
287 };
288 
296 template<class T>
298 T 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 
308 template <class T> Matrix wedge(const Vector& x);
309 
316 template <class T>
317 T expm(const Vector& x, int K=7) {
318  Matrix xhat = wedge<T>(x);
319  return T(expm(xhat,K));
320 }
321 
326 template <typename T>
327 T interpolate(const T& X, const T& Y, double t,
328  typename MakeOptionalJacobian<T, T>::type Hx = {},
329  typename MakeOptionalJacobian<T, T>::type Hy = {}) {
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 
351 template<class T>
353 {
354 private:
355  typename T::Jacobian adjointMap_;
356 public:
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>;
tag to assert a type is a manifold
Definition: Manifold.h:30
Class between_default(const Class &l1, const Class &l2)
Definition: Lie.h:240
Concept check class for variable types with Group properties.
Class expmap(const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
expmap with optional derivatives
Definition: Lie.h:89
tag to assert a type is a Lie group
Definition: Lie.h:164
Definition: Testable.h:152
TangentVector localCoordinates(const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
localCoordinates with optional derivatives
Definition: Lie.h:152
Definition: Group.h:43
Definition: Group.h:49
T BCH(const T &X, const T &Y)
AGC: bracket() only appears in Rot3 tests, should this be used elsewhere?
Definition: Lie.h:298
Definition: Lie.h:260
Definition: Lie.h:37
T expm(const Vector &x, int K=7)
Definition: Lie.h:317
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g ...
Definition: Lie.h:136
Extra manifold traits for fixed-dimension types.
Definition: Manifold.h:72
static Class Retract(const TangentVector &v, ChartJacobian H)
Retract at origin with optional derivative.
Definition: Lie.h:121
Matrix wedge(const Vector &x)
Base class and basic functions for Manifold types.
Group operator syntax flavors.
Definition: Group.h:40
Class expmap_default(const Class &t, const Vector &d)
Definition: Lie.h:252
Class retract(const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
retract with optional derivatives
Definition: Lie.h:141
Definition: chartTesting.h:28
Definition: OptionalJacobian.h:38
Both LieGroupTraits and Testable.
Definition: Lie.h:229
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Definition: Lie.h:131
static TangentVector LocalCoordinates(const Class &g)
LocalCoordinates at origin: possible in Lie group because it has an identity.
Definition: Lie.h:116
Definition: Lie.h:174
Definition: Lie.h:352
static Class Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
Definition: Lie.h:111
Class expmap(const TangentVector &v) const
Definition: Lie.h:78
TangentVector logmap(const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
logmap with optional derivatives
Definition: Lie.h:100
TangentVector logmap(const Class &g) const
Definition: Lie.h:84
tag to assert a type is a group
Definition: Group.h:37
static TangentVector LocalCoordinates(const Class &g, ChartJacobian H)
LocalCoordinates at origin with optional derivative.
Definition: Lie.h:126
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={})
Definition: Lie.h:327
Vector logmap_default(const Class &l0, const Class &lp)
Definition: Lie.h:246