2010-08-20 04:03:06 +08:00
|
|
|
|
/**
|
|
|
|
|
|
* @file Lie.h
|
|
|
|
|
|
* @brief Base class and basic functions for Lie types
|
|
|
|
|
|
* @author Richard Roberts
|
|
|
|
|
|
* @author Alex Cunningham
|
2010-01-08 08:40:17 +08:00
|
|
|
|
*/
|
|
|
|
|
|
|
2010-01-14 13:58:58 +08:00
|
|
|
|
#pragma once
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
2010-01-10 14:35:16 +08:00
|
|
|
|
#include <string>
|
2010-08-20 04:03:06 +08:00
|
|
|
|
|
2010-08-20 01:23:19 +08:00
|
|
|
|
#include <gtsam/base/Matrix.h>
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
|
|
|
|
|
namespace gtsam {
|
|
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
|
/**
|
|
|
|
|
|
* These core global functions can be specialized by new Lie types
|
|
|
|
|
|
* for better performance.
|
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
|
|
|
|
/* Exponential map about identity */
|
2010-01-08 08:40:17 +08:00
|
|
|
|
template<class T>
|
2010-08-20 04:03:06 +08:00
|
|
|
|
T expmap(const Vector& v) { return T::Expmap(v); }
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
|
/* Logmap (inverse exponential map) about identity */
|
|
|
|
|
|
template<class T>
|
|
|
|
|
|
Vector logmap(const T& p) { return T::Logmap(p); }
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
|
/** Compute l1 s.t. l2=l1*l0 */
|
2010-01-08 08:40:17 +08:00
|
|
|
|
template<class T>
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
|
inline T between(const T& l1, const T& l2) { return compose(inverse(l1),l2); }
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
|
/** Log map centered at l0, s.t. exp(l0,log(l0,lp)) = lp */
|
2010-01-08 08:40:17 +08:00
|
|
|
|
template<class T>
|
|
|
|
|
|
inline Vector logmap(const T& l0, const T& lp) { return logmap(between(l0,lp)); }
|
|
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
|
/** Exponential map centered at l0, s.t. exp(t,d) = t*exp(d) */
|
2010-01-08 08:40:17 +08:00
|
|
|
|
template<class T>
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
|
inline T expmap(const T& t, const Vector& d) { return compose(t,expmap<T>(d)); }
|
2010-01-08 08:40:17 +08:00
|
|
|
|
|
2010-01-10 07:15:06 +08:00
|
|
|
|
/**
|
|
|
|
|
|
* Base class for Lie group type
|
2010-08-20 04:03:06 +08:00
|
|
|
|
* This class uses the Curiously Recurring Template design pattern to allow
|
|
|
|
|
|
* for static polymorphism.
|
|
|
|
|
|
*
|
|
|
|
|
|
* T is the derived Lie type, like Point2, Pose3, etc.
|
|
|
|
|
|
*
|
|
|
|
|
|
* By convention, we use capital letters to designate a static function
|
|
|
|
|
|
*
|
|
|
|
|
|
* FIXME: Need to find a way to check for actual implementations in T
|
|
|
|
|
|
* so that there are no recursive function calls. This could be handled
|
|
|
|
|
|
* by not using the same name
|
2010-01-10 07:15:06 +08:00
|
|
|
|
*/
|
|
|
|
|
|
template <class T>
|
|
|
|
|
|
class Lie {
|
|
|
|
|
|
public:
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
* Returns dimensionality of the tangent space
|
|
|
|
|
|
*/
|
2010-08-20 04:03:06 +08:00
|
|
|
|
inline size_t dim() const {
|
|
|
|
|
|
return static_cast<const T*>(this)->dim();
|
|
|
|
|
|
}
|
2010-01-10 07:15:06 +08:00
|
|
|
|
|
|
|
|
|
|
/**
|
2010-08-20 04:03:06 +08:00
|
|
|
|
* Returns Exponential map update of T
|
|
|
|
|
|
* Default implementation calls global binary function
|
2010-01-10 07:15:06 +08:00
|
|
|
|
*/
|
|
|
|
|
|
T expmap(const Vector& v) const;
|
|
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
|
/** expmap around identity */
|
|
|
|
|
|
static T Expmap(const Vector& v) {
|
|
|
|
|
|
return T::Expmap(v);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
2010-01-10 07:15:06 +08:00
|
|
|
|
/**
|
|
|
|
|
|
* Returns Log map
|
2010-08-20 04:03:06 +08:00
|
|
|
|
* Default Implementation calls global binary function
|
2010-01-10 07:15:06 +08:00
|
|
|
|
*/
|
|
|
|
|
|
Vector logmap(const T& lp) const;
|
|
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
|
/** Logmap around identity */
|
|
|
|
|
|
static Vector Logmap(const T& p) {
|
|
|
|
|
|
return T::Logmap(p);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/** compose with another object */
|
|
|
|
|
|
inline T compose(const T& p) const {
|
|
|
|
|
|
return static_cast<const T*>(this)->compose(p);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/** invert the object and yield a new one */
|
|
|
|
|
|
inline T inverse() const {
|
|
|
|
|
|
return static_cast<const T*>(this)->inverse();
|
|
|
|
|
|
}
|
|
|
|
|
|
|
2010-01-10 07:15:06 +08:00
|
|
|
|
};
|
2010-01-10 14:35:16 +08:00
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
|
/** get the dimension of an object with a global function */
|
|
|
|
|
|
template<class T>
|
|
|
|
|
|
inline size_t dim(const T& object) {
|
|
|
|
|
|
return object.dim();
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/** compose two Lie types */
|
|
|
|
|
|
template<class T>
|
|
|
|
|
|
inline T compose(const T& p1, const T& p2) {
|
|
|
|
|
|
return p1.compose(p2);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/** invert an object */
|
|
|
|
|
|
template<class T>
|
|
|
|
|
|
inline T inverse(const T& p) {
|
|
|
|
|
|
return p.inverse();
|
|
|
|
|
|
}
|
|
|
|
|
|
|
2010-01-10 14:35:16 +08:00
|
|
|
|
/** Call print on the object */
|
|
|
|
|
|
template<class T>
|
2010-08-20 04:03:06 +08:00
|
|
|
|
inline void print(const T& object, const std::string& s = "") {
|
2010-01-10 14:35:16 +08:00
|
|
|
|
object.print(s);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/** Call equal on the object */
|
|
|
|
|
|
template<class T>
|
|
|
|
|
|
inline bool equal(const T& obj1, const T& obj2, double tol) {
|
|
|
|
|
|
return obj1.equals(obj2, tol);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/** Call equal on the object without tolerance (use default tolerance) */
|
|
|
|
|
|
template<class T>
|
|
|
|
|
|
inline bool equal(const T& obj1, const T& obj2) {
|
2010-01-11 06:41:23 +08:00
|
|
|
|
return obj1.equals(obj2);
|
2010-01-10 14:35:16 +08:00
|
|
|
|
}
|
|
|
|
|
|
|
2010-02-27 22:58:54 +08:00
|
|
|
|
/**
|
2010-08-20 04:03:06 +08:00
|
|
|
|
* Three term approximation of the Baker<EFBFBD>Campbell<EFBFBD>Hausdorff formula
|
2010-02-27 22:58:54 +08:00
|
|
|
|
* In non-commutative Lie groups, when composing exp(Z) = exp(X)exp(Y)
|
|
|
|
|
|
* it is not true that Z = X+Y. Instead, Z can be calculated using the BCH
|
|
|
|
|
|
* formula: Z = X + Y + [X,Y]/2 + [X-Y,[X,Y]]/12 - [Y,[X,[X,Y]]]/24
|
2010-08-20 04:03:06 +08:00
|
|
|
|
* http://en.wikipedia.org/wiki/Baker<65>Campbell<6C>Hausdorff_formula
|
2010-02-27 22:58:54 +08:00
|
|
|
|
*/
|
|
|
|
|
|
template<class T>
|
|
|
|
|
|
T BCH(const T& X, const T& Y) {
|
|
|
|
|
|
static const double _2 = 1. / 2., _12 = 1. / 12., _24 = 1. / 24.;
|
|
|
|
|
|
T X_Y = bracket(X, Y);
|
|
|
|
|
|
return X + Y + _2 * X_Y + _12 * bracket(X - Y, X_Y) - _24 * bracket(Y,
|
|
|
|
|
|
bracket(X, X_Y));
|
|
|
|
|
|
}
|
|
|
|
|
|
|
2010-03-02 10:25:27 +08:00
|
|
|
|
/**
|
|
|
|
|
|
* Declaration of wedge (see Murray94book) used to convert
|
|
|
|
|
|
* from n exponential coordinates to n*n element of the Lie algebra
|
|
|
|
|
|
*/
|
|
|
|
|
|
template <class T> Matrix wedge(const Vector& x);
|
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
* Exponential map given exponential coordinates
|
|
|
|
|
|
* class T needs a wedge<> function and a constructor from Matrix
|
|
|
|
|
|
* @param x exponential coordinates, vector of size n
|
|
|
|
|
|
* @ return a T
|
|
|
|
|
|
*/
|
|
|
|
|
|
template <class T>
|
|
|
|
|
|
T expm(const Vector& x, int K=7) {
|
|
|
|
|
|
Matrix xhat = wedge<T>(x);
|
|
|
|
|
|
return expm(xhat,K);
|
|
|
|
|
|
}
|
|
|
|
|
|
|
2010-01-14 13:58:58 +08:00
|
|
|
|
} // namespace gtsam
|