Lie/Manifold documentation

release/4.3a0
Alex Cunningham 2011-11-14 17:57:12 +00:00
parent 83ccc6211e
commit 8cf2b84f5a
3 changed files with 165 additions and 148 deletions

View File

@ -2,8 +2,6 @@
* @file Group.h
*
* @brief Concept check class for variable types with Group properties
* A Group concept extends a Manifold
*
* @date Nov 5, 2011
* @author Alex Cunningham
*/
@ -13,7 +11,8 @@
namespace gtsam {
/**
* Concept check for general Group structure
* This concept check enforces a Group structure on a variable type,
* in which we require the existence of basic algebraic operations.
*/
template<class T>
class GroupConcept {

View File

@ -14,28 +14,6 @@
* @brief Base class and basic functions for Lie types
* @author Richard Roberts
* @author Alex Cunningham
*
* This concept check provides a specialization on the Manifold type,
* in which the Manifolds represented require an algebra and group structure.
* All Lie types must also be a Manifold.
*
* The necessary functions to implement for Lie are defined
* below with additional details as to the interface. The
* concept checking function in class Lie will check whether or not
* the function exists and throw compile-time errors.
*
* Expmap around identity
* static T Expmap(const Vector& v);
*
*
* Logmap around identity
* static Vector Logmap(const T& p);
*
* Compute l0 s.t. l2=l1*l0, where (*this) is l1
* A default implementation of between(*this, lp) is available:
* between_default()
* T between(const T& l2) const;
*
*/
@ -66,9 +44,35 @@ namespace gtsam {
/**
* Concept check class for Lie group type
*
* T is the Lie type, like Point2, Pose3, etc.
* This concept check provides a specialization on the Manifold type,
* in which the Manifolds represented require an algebra and group structure.
* All Lie types must also be a Manifold.
*
* The necessary functions to implement for Lie are defined
* below with additional details as to the interface. The
* concept checking function in class Lie will check whether or not
* the function exists and throw compile-time errors.
*
* The exponential map is a specific retraction for Lie groups,
* which maps the tangent space in canonical coordinates back to
* the underlying manifold. Because we can enforce a group structure,
* a retraction of delta v, with tangent space centered at x1 can be performed
* as x2 = x1.compose(Expmap(v)).
*
* Expmap around identity
* static T Expmap(const Vector& v);
*
* Logmap around identity
* static Vector Logmap(const T& p);
*
* Compute l0 s.t. l2=l1*l0, where (*this) is l1
* A default implementation of between(*this, lp) is available:
* between_default()
* T between(const T& l2) const;
*
* By convention, we use capital letters to designate a static function
*
* @tparam T is a Lie type, like Point2, Pose3, etc.
*/
template <class T>
class LieConcept {

View File

@ -12,23 +12,7 @@
/**
* @file Manifold.h
* @brief Base class and basic functions for Manifold types
* @author Richard Roberts
* @author Alex Cunningham
*
* The necessary functions to implement for Manifold are defined
* below with additional details as to the interface. The
* concept checking function in class Manifold will check whether or not
* the function exists and throw compile-time errors.
*
* Returns dimensionality of the tangent space
* inline size_t dim() const;
*
* Returns Retraction update of T
* T retract(const Vector& v) const;
*
* Returns inverse retraction operation
* Vector localCoordinates(const T& lp) const;
*
*/
#pragma once
@ -43,9 +27,39 @@ namespace gtsam {
* Requires a mapping between a linear tangent space and the underlying
* manifold, of which Lie is a specialization.
*
* T is the Manifold type, like Point2, Pose3, etc.
* The necessary functions to implement for Manifold are defined
* below with additional details as to the interface. The
* concept checking function in class Manifold will check whether or not
* the function exists and throw compile-time errors.
*
* A manifold defines a space in which there is a notion of a linear tangent space
* that can be centered around a given point on the manifold. These nonlinear
* spaces may have such properties as wrapping around (as is the case with rotations),
* which might make linear operations on parameters not return a viable element of
* the manifold.
*
* We perform optimization by computing a linear delta in the tangent space of the
* current estimate, and then apply this change using a retraction operation, which
* maps the change in tangent space back to the manifold itself.
*
* There may be multiple possible retractions for a given manifold, which can be chosen
* between depending on the computational complexity. The important criteria for
* the creation for the retract and localCoordinates functions is that they be
* inverse operations.
*
* Returns dimensionality of the tangent space, which may be smaller than the number
* of nonlinear parameters.
* size_t dim() const;
*
* Returns a new T that is a result of updating *this with the delta v after pulling
* the updated value back to the manifold T.
* T retract(const Vector& v) const;
*
* Returns the linear coordinates of lp in the tangent space centered around *this.
* Vector localCoordinates(const T& lp) const;
*
* By convention, we use capital letters to designate a static function
* @tparam T is a Lie type, like Point2, Pose3, etc.
*/
template <class T>
class ManifoldConcept {