36 template <
class Class,
int N>
39 enum { dimension = N };
41 typedef Eigen::Matrix<double, N, N> Jacobian;
42 typedef Eigen::Matrix<double, N, 1> TangentVector;
44 const Class & derived()
const {
45 return static_cast<const Class&
>(*this);
48 Class compose(
const Class& g)
const {
52 Class between(
const Class& g)
const {
53 return derived().inverse() * g;
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();
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();
71 Class inverse(ChartJacobian H)
const {
72 if (H) *H = - derived().AdjointMap();
73 return derived().inverse();
78 Class
expmap(
const TangentVector& v)
const {
79 return compose(Class::Expmap(v));
84 TangentVector
logmap(
const Class& g)
const {
85 return Class::Logmap(between(g));
90 ChartJacobian H1, ChartJacobian H2 = {})
const {
92 Class g = Class::Expmap(v,H2 ? &D_g_v : 0);
94 if (H1) *H1 = g.inverse().AdjointMap();
101 ChartJacobian H1, ChartJacobian H2 = {})
const {
102 Class h = between(g);
104 TangentVector v = Class::Logmap(h, (H1 || H2) ? &D_v_h : 0);
105 if (H1) *H1 = - D_v_h * h.inverse().AdjointMap();
111 static Class
Retract(
const TangentVector& v) {
112 return Class::ChartAtOrigin::Retract(v);
117 return Class::ChartAtOrigin::Local(g);
121 static Class
Retract(
const TangentVector& v, ChartJacobian H) {
122 return Class::ChartAtOrigin::Retract(v,H);
127 return Class::ChartAtOrigin::Local(g,H);
132 return compose(Class::ChartAtOrigin::Retract(v));
137 return Class::ChartAtOrigin::Local(between(g));
142 ChartJacobian H1, ChartJacobian H2 = {})
const {
144 Class g = Class::ChartAtOrigin::Retract(v, H2 ? &D_g_v : 0);
145 Class h = compose(g);
146 if (H1) *H1 = g.inverse().AdjointMap();
153 ChartJacobian H1, ChartJacobian H2 = {})
const {
154 Class h = between(g);
156 TangentVector v = Class::ChartAtOrigin::Local(h, (H1 || H2) ? &D_v_h : 0);
157 if (H1) *H1 = - D_v_h * h.inverse().AdjointMap();
173 template<
class Class>
180 static Class Identity() {
return Class::Identity();}
185 typedef Class ManifoldType;
186 enum { dimension = Class::dimension };
187 typedef Eigen::Matrix<double, dimension, 1> TangentVector;
190 static TangentVector Local(
const Class& origin,
const Class& other,
191 ChartJacobian Horigin = {}, ChartJacobian Hother = {}) {
192 return origin.localCoordinates(other, Horigin, Hother);
195 static Class
Retract(
const Class& origin,
const TangentVector& v,
196 ChartJacobian Horigin = {}, ChartJacobian Hv = {}) {
197 return origin.retract(v, Horigin, Hv);
203 static TangentVector Logmap(
const Class& m, ChartJacobian Hm = {}) {
204 return Class::Logmap(m, Hm);
207 static Class Expmap(
const TangentVector& v, ChartJacobian Hv = {}) {
208 return Class::Expmap(v, Hv);
211 static Class Compose(
const Class& m1,
const Class& m2,
212 ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
213 return m1.compose(m2, H1, H2);
216 static Class Between(
const Class& m1,
const Class& m2,
217 ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
218 return m1.between(m2, H1, H2);
221 static Class Inverse(
const Class& m,
222 ChartJacobian H = {}) {
239 template<
class Class>
241 return l1.inverse().compose(l2);
245 template<
class Class>
247 return Class::Logmap(l0.between(lp));
251 template<
class Class>
253 return t.compose(Class::Expmap(d));
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)");
286 ChartJacobian Hg, Hh;
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)));
308 template <
class T> Matrix
wedge(
const Vector& x);
317 T
expm(
const Vector& x,
int K=7) {
318 Matrix xhat = wedge<T>(x);
319 return T(
expm(xhat,K));
326 template <
typename T>
331 typename MakeJacobian<T, T>::type between_H_x, log_H, exp_H, compose_H_x;
337 X, Delta, compose_H_x);
339 if (Hx) *Hx = compose_H_x + t * exp_H * log_H * between_H_x;
340 if (Hy) *Hy = t * exp_H * log_H;
355 typename T::Jacobian adjointMap_;
358 typename T::Jacobian operator()(
const typename T::Jacobian &covariance)
359 {
return adjointMap_ * covariance * adjointMap_.transpose(); }
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
T BCH(const T &X, const T &Y)
AGC: bracket() only appears in Rot3 tests, should this be used elsewhere?
Definition: Lie.h:298
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
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