Manifold.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 
20 #pragma once
21 
22 #include <gtsam/base/Matrix.h>
23 #include <gtsam/base/Testable.h>
25 
26 #include <boost/concept_check.hpp>
27 #include <boost/concept/requires.hpp>
28 #include <boost/type_traits/is_base_of.hpp>
29 
30 namespace gtsam {
31 
33 struct manifold_tag {};
34 
53 template <typename T> struct traits;
54 
55 namespace internal {
56 
58 template<class Class>
60 
61  enum { dim = Class::dimension };
62 
63  Class p, q;
66 
68  v = p.localCoordinates(q);
69  q = p.retract(v);
70  }
71 };
72 
74 template<class Class, int N>
76  // Compile-time dimensionality
77  static int GetDimension(const Class&) {
78  return N;
79  }
80 };
81 
83 template<class Class>
85  // Run-time dimensionality
86  static int GetDimension(const Class& m) {
87  return m.dim();
88  }
89 };
90 
94 template<class Class>
95 struct ManifoldTraits: GetDimensionImpl<Class, Class::dimension> {
96 
97  // Check that Class has the necessary machinery
99 
100  // Dimension of the manifold
101  enum { dimension = Class::dimension };
102 
103  // Typedefs required by all manifold types.
107 
108  // Local coordinates
109  static TangentVector Local(const Class& origin, const Class& other) {
110  return origin.localCoordinates(other);
111  }
112 
113  // Retraction back to manifold
114  static Class Retract(const Class& origin, const TangentVector& v) {
115  return origin.retract(v);
116  }
117 };
118 
120 template<class Class> struct Manifold: ManifoldTraits<Class>, Testable<Class> {};
121 
122 } // \ namespace internal
123 
125 template<typename T>
127 check_manifold_invariants(const T& a, const T& b, double tol=1e-9) {
130  T c = traits<T>::Retract(a,v);
131  return v0.norm() < tol && traits<T>::Equals(b,c,tol);
132 }
133 
135 template<typename T>
136 class IsManifold {
137 
138 public:
139 
140  typedef typename traits<T>::structure_category structure_category_tag;
141  static const int dim = traits<T>::dimension;
142  typedef typename traits<T>::ManifoldType ManifoldType;
143  typedef typename traits<T>::TangentVector TangentVector;
144 
145  BOOST_CONCEPT_USAGE(IsManifold) {
146  BOOST_STATIC_ASSERT_MSG(
148  "This type's structure_category trait does not assert it as a manifold (or derived)");
149  BOOST_STATIC_ASSERT(TangentVector::SizeAtCompileTime == dim);
150 
151  // make sure Chart methods are defined
152  v = traits<T>::Local(p, q);
153  q = traits<T>::Retract(p, v);
154  }
155 
156 private:
157 
158  TangentVector v;
159  ManifoldType p, q;
160 };
161 
163 template<typename T>
165  typedef const int value_type;
166  static const int value = traits<T>::dimension;
167  BOOST_STATIC_ASSERT_MSG(value != Eigen::Dynamic,
168  "FixedDimension instantiated for dymanically-sized type.");
169 };
170 } // \ namespace gtsam
171 
173 // * Macros for using the ManifoldConcept
174 // * - An instantiation for use inside unit tests
175 // * - A typedef for use inside generic algorithms
176 // *
177 // * NOTE: intentionally not in the gtsam namespace to allow for classes not in
178 // * the gtsam namespace to be more easily enforced as testable
179 // */
180 #define GTSAM_CONCEPT_MANIFOLD_INST(T) template class gtsam::IsManifold<T>;
181 #define GTSAM_CONCEPT_MANIFOLD_TYPE(T) typedef gtsam::IsManifold<T> _gtsam_IsManifold_##T;
Matrix3f m
tag to assert a type is a manifold
Definition: Manifold.h:33
Both ManifoldTraits and Testable.
Definition: Manifold.h:120
Eigen::Matrix< double, dimension, 1 > TangentVector
Definition: Manifold.h:106
Requirements on type to pass it to Manifold template below.
Definition: Manifold.h:59
Concept check for values that can be used in unit tests.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set origin
Eigen::Matrix< double, dim, 1 > v
Definition: Manifold.h:64
const int value_type
Definition: Manifold.h:165
ArrayXcf v
Definition: Cwise_arg.cpp:1
Give fixed size dimension of a type, fails at compile time if dynamic.
Definition: Manifold.h:164
BOOST_CONCEPT_ASSERT((boost::RandomAccessRangeConcept< ListOfOneContainer< int > >))
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
#define N
Definition: gksort.c:12
Array33i a
Extra manifold traits for fixed-dimension types.
Definition: Manifold.h:75
BOOST_CONCEPT_USAGE(HasManifoldPrereqs)
Definition: Manifold.h:67
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
const G & b
Definition: Group.h:83
static int GetDimension(const Class &)
Definition: Manifold.h:77
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
traits
Definition: chartTesting.h:28
OptionalJacobian< dim, dim > Hv
Definition: Manifold.h:65
static const double v0
float * p
static Class Retract(const Class &origin, const TangentVector &v)
Definition: Manifold.h:114
static TangentVector Local(const Class &origin, const Class &other)
Definition: Manifold.h:109
Special class for optional Jacobian arguments.
const G double tol
Definition: Group.h:83
const int Dynamic
Definition: Constants.h:21
BOOST_CONCEPT_REQUIRES(((IsGroup< G >)),(bool)) check_group_invariants(const G &a
Check invariants.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:35