19template<
typename T>
struct traits;
24template<
class Class,
int N>
29 typedef Eigen::Matrix<double, N, 1> TangentVector;
31 typedef Eigen::Matrix<double, N, N> Jacobian;
32 static int GetDimension(
const Class&) {
return N;}
34 static TangentVector Local(
const Class& origin,
const Class& other,
36 if (H1) *H1 = - Jacobian::Identity();
37 if (H2) *H2 = Jacobian::Identity();
38 Class v = other-origin;
42 static Class Retract(
const Class& origin,
const TangentVector& v,
44 if (H1) *H1 = Jacobian::Identity();
45 if (H2) *H2 = Jacobian::Identity();
54 static TangentVector Logmap(
const Class& m,
ChartJacobian Hm = boost::none) {
55 if (Hm) *Hm = Jacobian::Identity();
59 static Class Expmap(
const TangentVector& v,
ChartJacobian Hv = boost::none) {
60 if (Hv) *Hv = Jacobian::Identity();
64 static Class Compose(
const Class& v1,
const Class& v2,
ChartJacobian H1 = boost::none,
66 if (H1) *H1 = Jacobian::Identity();
67 if (H2) *H2 = Jacobian::Identity();
71 static Class Between(
const Class& v1,
const Class& v2,
ChartJacobian H1 = boost::none,
73 if (H1) *H1 = - Jacobian::Identity();
74 if (H2) *H2 = Jacobian::Identity();
78 static Class Inverse(
const Class& v,
ChartJacobian H = boost::none) {
79 if (H) *H = - Jacobian::Identity();
92 static Class Compose(
const Class& v1,
const Class& v2) {
return v1+v2;}
93 static Class Between(
const Class& v1,
const Class& v2) {
return v2-v1;}
94 static Class Inverse(
const Class& m) {
return -m;}
99 typedef Eigen::VectorXd TangentVector;
101 static int GetDimension(
const Class& m) {
return m.dim();}
103 static Eigen::MatrixXd Eye(
const Class& m) {
104 int dim = GetDimension(m);
105 return Eigen::MatrixXd::Identity(dim, dim);
108 static TangentVector Local(
const Class& origin,
const Class& other,
110 if (H1) *H1 = - Eye(origin);
111 if (H2) *H2 = Eye(other);
112 Class v = other-origin;
116 static Class Retract(
const Class& origin,
const TangentVector& v,
118 if (H1) *H1 = Eye(origin);
119 if (H2) *H2 = Eye(origin);
128 static TangentVector Logmap(
const Class& m,
ChartJacobian Hm = boost::none) {
129 if (Hm) *Hm = Eye(m);
133 static Class Expmap(
const TangentVector& v,
ChartJacobian Hv = boost::none) {
140 static Class Compose(
const Class& v1,
const Class& v2,
ChartJacobian H1,
142 if (H1) *H1 = Eye(v1);
143 if (H2) *H2 = Eye(v2);
147 static Class Between(
const Class& v1,
const Class& v2,
ChartJacobian H1,
149 if (H1) *H1 = - Eye(v1);
150 if (H2) *H2 = Eye(v2);
166 enum { dim = Class::dimension };
172 p = Class::identity();
195 static Class Identity() {
return Class::identity();}
200 enum { dimension = Class::dimension};
201 typedef Class ManifoldType;
211template<
typename Scalar>
218 static void Print(Scalar m,
const std::string& str =
"") {
221 static bool Equals(Scalar v1, Scalar v2,
double tol = 1e-8) {
222 return std::abs(v1 - v2) < tol;
229 static Scalar Identity() {
return 0;}
234 typedef Scalar ManifoldType;
235 enum { dimension = 1 };
236 typedef Eigen::Matrix<double, 1, 1> TangentVector;
239 static TangentVector Local(Scalar origin, Scalar other,
241 if (H1) (*H1)[0] = -1.0;
242 if (H2) (*H2)[0] = 1.0;
243 TangentVector result;
244 result(0) = other - origin;
248 static Scalar Retract(Scalar origin,
const TangentVector& v,
250 if (H1) (*H1)[0] = 1.0;
251 if (H2) (*H2)[0] = 1.0;
252 return origin + v[0];
258 static TangentVector Logmap(Scalar m,
ChartJacobian H = boost::none) {
259 if (H) (*H)[0] = 1.0;
263 static Scalar Expmap(
const TangentVector& v,
ChartJacobian H = boost::none) {
264 if (H) (*H)[0] = 1.0;
282template<
int M,
int N,
int Options,
int MaxRows,
int MaxCols>
283struct traits<Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> > :
285 Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols>, M * N> {
288 typedef Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> Fixed;
292 static void Print(
const Fixed& m,
const std::string& str =
"") {
295 static bool Equals(
const Fixed& v1,
const Fixed& v2,
double tol = 1e-8) {
303 static Fixed Identity() {
return Fixed::Zero();}
308 enum { dimension = M*N};
309 typedef Fixed ManifoldType;
310 typedef Eigen::Matrix<double, dimension, 1> TangentVector;
311 typedef Eigen::Matrix<double, dimension, dimension> Jacobian;
314 static TangentVector Local(
const Fixed& origin,
const Fixed& other,
316 if (H1) (*H1) = -Jacobian::Identity();
317 if (H2) (*H2) = Jacobian::Identity();
318 TangentVector result;
319 Eigen::Map<Fixed>(result.data()) = other - origin;
323 static Fixed Retract(
const Fixed& origin,
const TangentVector& v,
325 if (H1) (*H1) = Jacobian::Identity();
326 if (H2) (*H2) = Jacobian::Identity();
327 return origin + Eigen::Map<const Fixed>(v.data());
333 static TangentVector Logmap(
const Fixed& m,
ChartJacobian H = boost::none) {
334 if (H) *H = Jacobian::Identity();
335 TangentVector result;
336 Eigen::Map<Fixed>(result.data()) = m;
340 static Fixed Expmap(
const TangentVector& v,
ChartJacobian H = boost::none) {
343 if (H) *H = Jacobian::Identity();
344 return m + Eigen::Map<const Fixed>(v.data());
353template<
int M,
int N,
int Options,
int MaxRows,
int MaxCols>
357 typedef Eigen::Matrix<double, M, N, Options, MaxRows, MaxCols> Dynamic;
361 static void Print(
const Dynamic& m,
const std::string& str =
"") {
364 static bool Equals(
const Dynamic& v1,
const Dynamic& v2,
373 static Dynamic Identity() {
374 throw std::runtime_error(
"Identity not defined for dynamic types");
380 enum { dimension = Eigen::Dynamic };
381 typedef Eigen::VectorXd TangentVector;
382 typedef Eigen::MatrixXd Jacobian;
384 typedef Dynamic ManifoldType;
386 static int GetDimension(
const Dynamic& m) {
387 return m.rows() * m.
cols();
390 static Jacobian Eye(
const Dynamic& m) {
391 int dim = GetDimension(m);
392 return Eigen::Matrix<double, dimension, dimension>::Identity(dim, dim);
395 static TangentVector Local(
const Dynamic& m,
const Dynamic& other,
397 if (H1) *H1 = -Eye(m);
398 if (H2) *H2 = Eye(m);
399 TangentVector v(GetDimension(m));
400 Eigen::Map<Dynamic>(v.data(), m.rows(), m.cols()) = other - m;
404 static Dynamic Retract(
const Dynamic& m,
const TangentVector& v,
406 if (H1) *H1 = Eye(m);
407 if (H2) *H2 = Eye(m);
408 return m + Eigen::Map<const Dynamic>(v.data(), m.rows(), m.cols());
414 static TangentVector Logmap(
const Dynamic& m,
ChartJacobian H = boost::none) {
416 TangentVector result(GetDimension(m));
417 Eigen::Map<Dynamic>(result.data(), m.cols(), m.rows()) = m;
421 static Dynamic Expmap(
const TangentVector& ,
ChartJacobian H = boost::none) {
422 static_cast<void>(H);
423 throw std::runtime_error(
"Expmap not defined for dynamic types");
426 static Dynamic Inverse(
const Dynamic& m,
ChartJacobian H = boost::none) {
431 static Dynamic Compose(
const Dynamic& v1,
const Dynamic& v2,
433 if (H1) *H1 = Eye(v1);
434 if (H2) *H2 = Eye(v1);
438 static Dynamic Between(
const Dynamic& v1,
const Dynamic& v2,
440 if (H1) *H1 = -Eye(v1);
441 if (H2) *H2 = Eye(v1);
451template<
int Options,
int MaxRows,
int MaxCols>
452struct traits<Eigen::Matrix<double, -1, -1, Options, MaxRows, MaxCols> > :
457template<
int Options,
int MaxRows,
int MaxCols>
458struct traits<Eigen::Matrix<double, -1, 1, Options, MaxRows, MaxCols> > :
463template<
int Options,
int MaxRows,
int MaxCols>
464struct traits<Eigen::Matrix<double, 1, -1, Options, MaxRows, MaxCols> > :
476 BOOST_STATIC_ASSERT_MSG(
477 (boost::is_base_of<vector_space_tag, structure_category_tag>::value),
478 "This type's trait does not assert it as a vector space (or derived)");
Base class and basic functions for Lie types.
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:155
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
equals with a tolerance
Definition: Matrix.h:84
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 Lie group
Definition: Lie.h:164
Lie Group Concept.
Definition: Lie.h:260
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
OptionalJacobian< Rows, N > cols(int startCol)
Access M*N sub-block if we are allocated, otherwise none TODO(frank): this could work as is below if ...
Definition: OptionalJacobian.h:151
Definition: OptionalJacobian.h:168
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:151
tag to assert a type is a vector space
Definition: VectorSpace.h:16
VectorSpaceTraits Implementation for Fixed sizes.
Definition: VectorSpace.h:25
Requirements on type to pass it to Manifold template below.
Definition: VectorSpace.h:164
A helper that implements the traits interface for classes that define vector spaces To use this for y...
Definition: VectorSpace.h:185
VectorSpace provides both Testable and VectorSpaceTraits.
Definition: VectorSpace.h:207
A helper that implements the traits interface for scalar vector spaces.
Definition: VectorSpace.h:212
Definition: VectorSpace.h:354
Vector Space concept.
Definition: VectorSpace.h:470