Classes | Public Types | Protected Types | Protected Attributes | List of all members
gtsam::SO< N > Class Template Reference

#include <SOn.h>

Inheritance diagram for gtsam::SO< N >:
Inheritance graph
[legend]

Classes

struct  ChartAtOrigin
 

Public Types

enum  { dimension = internal::DimensionSO(N) }
 
using MatrixDD = Eigen::Matrix< double, dimension, dimension >
 
using MatrixNN = Eigen::Matrix< double, N, N >
 
using VectorN2 = Eigen::Matrix< double, internal::NSquaredSO(N), 1 >
 
- Public Types inherited from gtsam::LieGroup< SO< N >, internal::DimensionSO(N)>
enum  
 
typedef OptionalJacobian< N, NChartJacobian
 
typedef Eigen::Matrix< double, N, NJacobian
 
typedef Eigen::Matrix< double, N, 1 > TangentVector
 

Public Member Functions

Standard methods
const MatrixNNmatrix () const
 Return matrix. More...
 
size_t rows () const
 
size_t cols () const
 
Testable
void print (const std::string &s=std::string()) const
 
bool equals (const SO &other, double tol) const
 
- Public Member Functions inherited from gtsam::LieGroup< SO< N >, internal::DimensionSO(N)>
SO< Nbetween (const SO< N > &g) const
 
SO< Nbetween (const SO< N > &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
SO< Ncompose (const SO< N > &g) const
 
SO< Ncompose (const SO< N > &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
const SO< N > & derived () const
 
SO< Nexpmap (const TangentVector &v) const
 
SO< Nexpmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 expmap with optional derivatives More...
 
SO< Ninverse (ChartJacobian H) const
 
TangentVector localCoordinates (const SO< N > &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g More...
 
TangentVector localCoordinates (const SO< N > &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 localCoordinates with optional derivatives More...
 
TangentVector logmap (const SO< N > &g) const
 
TangentVector logmap (const SO< N > &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 logmap with optional derivatives More...
 
SO< Nretract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this More...
 
SO< Nretract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 retract with optional derivatives More...
 

Protected Types

template<int N_>
using IsDynamic = typename std::enable_if< N_==Eigen::Dynamic, void >::type
 
template<int N_>
using IsFixed = typename std::enable_if< N_ >=2, void >::type
 
template<int N_>
using IsSO3 = typename std::enable_if< N_==3, void >::type
 

Protected Attributes

MatrixNN matrix_
 Rotation matrix. More...
 

Friends

Serialization
class boost::serialization::access
 
class Rot3
 
template<class Archive >
void save (Archive &, SO &, const unsigned int)
 
template<class Archive >
void load (Archive &, SO &, const unsigned int)
 
template<class Archive >
void serialize (Archive &, SO &, const unsigned int)
 

Constructors

template<int N_ = N, typename = IsFixed<N_>>
 SO ()
 Construct SO<N> identity for N >= 2. More...
 
template<int N_ = N, typename = IsDynamic<N_>>
 SO (size_t n=0)
 Construct SO<N> identity for N == Eigen::Dynamic. More...
 
template<typename Derived >
 SO (const Eigen::MatrixBase< Derived > &R)
 Constructor from Eigen Matrix, dynamic version. More...
 
template<int M, int N_ = N, typename = IsDynamic<N_>>
 SO (const SO< M > &R)
 Construct dynamic SO(n) from Fixed SO<M> More...
 
template<int N_ = N, typename = IsSO3<N_>>
 SO (const Eigen::AngleAxisd &angleAxis)
 Constructor from AngleAxisd. More...
 
template<typename Derived >
static SO FromMatrix (const Eigen::MatrixBase< Derived > &R)
 Named constructor from Eigen Matrix. More...
 
template<typename Derived , int N_ = N, typename = IsDynamic<N_>>
static SO Lift (size_t n, const Eigen::MatrixBase< Derived > &R)
 Named constructor from lower dimensional matrix. More...
 
static SO AxisAngle (const Vector3 &axis, double theta)
 Constructor from axis and angle. Only defined for SO3. More...
 
static SO ClosestTo (const MatrixNN &M)
 
static SO ChordalMean (const std::vector< SO > &rotations)
 
template<int N_ = N, typename = IsDynamic<N_>>
static SO Random (std::mt19937 &rng, size_t n=0)
 Random SO(n) element (no big claims about uniformity). SO(3) is specialized in SO3.cpp. More...
 
template<int N_ = N, typename = IsFixed<N_>>
static SO Random (std::mt19937 &rng)
 Random SO(N) element (no big claims about uniformity) More...
 

Group

SO operator* (const SO &other) const
 Multiplication. More...
 
SO inverse () const
 inverse of a rotation = transpose More...
 
template<int N_ = N, typename = IsFixed<N_>>
static SO identity ()
 SO<N> identity for N >= 2. More...
 
template<int N_ = N, typename = IsDynamic<N_>>
static SO identity (size_t n=0)
 SO<N> identity for N == Eigen::Dynamic. More...
 

Manifold

using TangentVector = Eigen::Matrix< double, dimension, 1 >
 
using ChartJacobian = OptionalJacobian< dimension, dimension >
 
size_t dim () const
 
static int Dim ()
 Return compile-time dimensionality: fixed size N or Eigen::Dynamic. More...
 
static size_t Dimension (size_t n)
 
static size_t AmbientDim (size_t d)
 
static MatrixNN Hat (const TangentVector &xi)
 
static void Hat (const Vector &xi, Eigen::Ref< MatrixNN > X)
 In-place version of Hat (see details there), implements recursion. More...
 
static TangentVector Vee (const MatrixNN &X)
 Inverse of Hat. See note about xi element order in Hat. More...
 
template<int N_ = N, typename = IsDynamic<N_>>
static MatrixDD IdentityJacobian (size_t n)
 

Lie Group

MatrixDD AdjointMap () const
 Adjoint map. More...
 
static SO Expmap (const TangentVector &omega, ChartJacobian H=boost::none)
 
static MatrixDD ExpmapDerivative (const TangentVector &omega)
 Derivative of Expmap, currently only defined for SO3. More...
 
static TangentVector Logmap (const SO &R, ChartJacobian H=boost::none)
 
static MatrixDD LogmapDerivative (const TangentVector &omega)
 Derivative of Logmap, currently only defined for SO3. More...
 

Other methods

VectorN2 vec (OptionalJacobian< internal::NSquaredSO(N), dimension > H=boost::none) const
 
template<int N_ = N, typename = IsFixed<N_>>
static Matrix VectorizedGenerators ()
 Calculate N^2 x dim matrix of vectorized Lie algebra generators for SO(N) More...
 
template<int N_ = N, typename = IsDynamic<N_>>
static Matrix VectorizedGenerators (size_t n=0)
 Calculate n^2 x dim matrix of vectorized Lie algebra generators for SO(n) More...
 

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::LieGroup< SO< N >, internal::DimensionSO(N)>
static TangentVector LocalCoordinates (const SO< N > &g)
 LocalCoordinates at origin: possible in Lie group because it has an identity. More...
 
static TangentVector LocalCoordinates (const SO< N > &g, ChartJacobian H)
 LocalCoordinates at origin with optional derivative. More...
 
static SO< NRetract (const TangentVector &v)
 Retract at origin: possible in Lie group because it has an identity. More...
 
static SO< NRetract (const TangentVector &v, ChartJacobian H)
 Retract at origin with optional derivative. More...
 

Detailed Description

template<int N>
class gtsam::SO< N >

Manifold of special orthogonal rotation matrices SO<N>. Template paramater N can be a fixed integer or can be Eigen::Dynamic

Definition at line 50 of file SOn.h.

Member Typedef Documentation

Definition at line 197 of file SOn.h.

template<int N>
template<int N_>
using gtsam::SO< N >::IsDynamic = typename std::enable_if<N_ == Eigen::Dynamic, void>::type
protected

Definition at line 65 of file SOn.h.

template<int N>
template<int N_>
using gtsam::SO< N >::IsFixed = typename std::enable_if<N_ >= 2, void>::type
protected

Definition at line 67 of file SOn.h.

template<int N>
template<int N_>
using gtsam::SO< N >::IsSO3 = typename std::enable_if<N_ == 3, void>::type
protected

Definition at line 69 of file SOn.h.

template<int N>
using gtsam::SO< N >::MatrixDD = Eigen::Matrix<double, dimension, dimension>

Definition at line 55 of file SOn.h.

template<int N>
using gtsam::SO< N >::MatrixNN = Eigen::Matrix<double, N, N>

Definition at line 53 of file SOn.h.

template<int N>
using gtsam::SO< N >::TangentVector = Eigen::Matrix<double, dimension, 1>

Definition at line 196 of file SOn.h.

template<int N>
using gtsam::SO< N >::VectorN2 = Eigen::Matrix<double, internal::NSquaredSO(N), 1>

Definition at line 54 of file SOn.h.

Member Enumeration Documentation

template<int N>
anonymous enum
Enumerator
dimension 

Definition at line 52 of file SOn.h.

Constructor & Destructor Documentation

template<int N>
template<int N_ = N, typename = IsFixed<N_>>
gtsam::SO< N >::SO ( )
inline

Construct SO<N> identity for N >= 2.

Definition at line 77 of file SOn.h.

template<int N>
template<int N_ = N, typename = IsDynamic<N_>>
gtsam::SO< N >::SO ( size_t  n = 0)
inlineexplicit

Construct SO<N> identity for N == Eigen::Dynamic.

Definition at line 81 of file SOn.h.

template<int N>
template<typename Derived >
gtsam::SO< N >::SO ( const Eigen::MatrixBase< Derived > &  R)
inlineexplicit

Constructor from Eigen Matrix, dynamic version.

Definition at line 89 of file SOn.h.

template<int N>
template<int M, int N_ = N, typename = IsDynamic<N_>>
gtsam::SO< N >::SO ( const SO< M > &  R)
inlineexplicit

Construct dynamic SO(n) from Fixed SO<M>

Definition at line 109 of file SOn.h.

template<int N>
template<int N_ = N, typename = IsSO3<N_>>
gtsam::SO< N >::SO ( const Eigen::AngleAxisd angleAxis)
inlineexplicit

Constructor from AngleAxisd.

Definition at line 113 of file SOn.h.

Member Function Documentation

template<int N>
SO< N >::MatrixDD gtsam::SO< N >::AdjointMap ( ) const

Adjoint map.

Definition at line 159 of file SO4.cpp.

template<int N>
static size_t gtsam::SO< N >::AmbientDim ( size_t  d)
inlinestatic

Definition at line 207 of file SOn.h.

template<int N>
static SO gtsam::SO< N >::AxisAngle ( const Vector3 axis,
double  theta 
)
static

Constructor from axis and angle. Only defined for SO3.

template<int N>
static SO gtsam::SO< N >::ChordalMean ( const std::vector< SO< N > > &  rotations)
static

Named constructor that finds chordal mean = argmin_R sqr(|R-R_i|_F), currently only defined for SO3.

template<int N>
static SO gtsam::SO< N >::ClosestTo ( const MatrixNN M)
static

Named constructor that finds SO(n) matrix closest to M in Frobenius norm, currently only defined for SO3.

template<int N>
size_t gtsam::SO< N >::cols ( void  ) const
inline

Definition at line 155 of file SOn.h.

template<int N>
static int gtsam::SO< N >::Dim ( )
inlinestatic

Return compile-time dimensionality: fixed size N or Eigen::Dynamic.

Definition at line 200 of file SOn.h.

template<int N>
size_t gtsam::SO< N >::dim ( ) const
inline

Definition at line 211 of file SOn.h.

template<int N>
static size_t gtsam::SO< N >::Dimension ( size_t  n)
inlinestatic

Definition at line 204 of file SOn.h.

template<int N>
bool gtsam::SO< N >::equals ( const SO< N > &  other,
double  tol 
) const
inline

Definition at line 163 of file SOn.h.

template<int N>
SO< N > gtsam::SO< N >::Expmap ( const TangentVector omega,
ChartJacobian  H = boost::none 
)
static

Exponential map at identity - create a rotation from canonical coordinates

Definition at line 67 of file SOn-inl.h.

template<int N>
SO< N >::MatrixDD gtsam::SO< N >::ExpmapDerivative ( const TangentVector omega)
static

Derivative of Expmap, currently only defined for SO3.

Definition at line 72 of file SOn-inl.h.

template<int N>
template<typename Derived >
static SO gtsam::SO< N >::FromMatrix ( const Eigen::MatrixBase< Derived > &  R)
inlinestatic

Named constructor from Eigen Matrix.

Definition at line 93 of file SOn.h.

template<int N>
SO< N >::MatrixNN gtsam::SO< N >::Hat ( const TangentVector xi)
static

Hat operator creates Lie algebra element corresponding to d-vector, where d is the dimensionality of the manifold. This function is implemented recursively, and the d-vector is assumed to laid out such that the last element corresponds to so(2), the last 3 to so(3), the last 6 to so(4) etc... For example, the vector-space isomorphic to so(5) is laid out as: a b c d | u v w | x y | z where the latter elements correspond to "telescoping" sub-algebras: 0 -z y w -d z 0 -x -v c -y x 0 u -b -w v -u 0 a d -c b -a 0 This scheme behaves exactly as expected for SO(2) and SO(3).

Definition at line 29 of file SOn-inl.h.

template<int N>
static void gtsam::SO< N >::Hat ( const Vector xi,
Eigen::Ref< MatrixNN X 
)
static

In-place version of Hat (see details there), implements recursion.

template<int N>
template<int N_ = N, typename = IsFixed<N_>>
static SO gtsam::SO< N >::identity ( )
inlinestatic

SO<N> identity for N >= 2.

Definition at line 179 of file SOn.h.

template<int N>
template<int N_ = N, typename = IsDynamic<N_>>
static SO gtsam::SO< N >::identity ( size_t  n = 0)
inlinestatic

SO<N> identity for N == Eigen::Dynamic.

Definition at line 185 of file SOn.h.

template<int N>
template<int N_ = N, typename = IsDynamic<N_>>
static MatrixDD gtsam::SO< N >::IdentityJacobian ( size_t  n)
inlinestatic

Definition at line 252 of file SOn.h.

template<int N>
SO gtsam::SO< N >::inverse ( ) const
inline

inverse of a rotation = transpose

Definition at line 190 of file SOn.h.

template<int N>
template<typename Derived , int N_ = N, typename = IsDynamic<N_>>
static SO gtsam::SO< N >::Lift ( size_t  n,
const Eigen::MatrixBase< Derived > &  R 
)
inlinestatic

Named constructor from lower dimensional matrix.

Definition at line 99 of file SOn.h.

template<int N>
SO< N >::TangentVector gtsam::SO< N >::Logmap ( const SO< N > &  R,
ChartJacobian  H = boost::none 
)
static

Log map at identity - returns the canonical coordinates of this rotation

Definition at line 77 of file SOn-inl.h.

template<int N>
SO< N >::MatrixDD gtsam::SO< N >::LogmapDerivative ( const TangentVector omega)
static

Derivative of Logmap, currently only defined for SO3.

Definition at line 82 of file SOn-inl.h.

template<int N>
const MatrixNN& gtsam::SO< N >::matrix ( ) const
inline

Return matrix.

Definition at line 152 of file SOn.h.

template<int N>
SO gtsam::SO< N >::operator* ( const SO< N > &  other) const
inline

Multiplication.

Definition at line 172 of file SOn.h.

template<int N>
void gtsam::SO< N >::print ( const std::string &  s = std::string()) const

Definition at line 108 of file SOn-inl.h.

template<int N>
template<int N_ = N, typename = IsDynamic<N_>>
static SO gtsam::SO< N >::Random ( std::mt19937 &  rng,
size_t  n = 0 
)
inlinestatic

Random SO(n) element (no big claims about uniformity). SO(3) is specialized in SO3.cpp.

Definition at line 128 of file SOn.h.

template<int N>
template<int N_ = N, typename = IsFixed<N_>>
static SO gtsam::SO< N >::Random ( std::mt19937 &  rng)
inlinestatic

Random SO(N) element (no big claims about uniformity)

Definition at line 142 of file SOn.h.

template<int N>
size_t gtsam::SO< N >::rows ( void  ) const
inline

Definition at line 154 of file SOn.h.

template<int N>
SO< N >::VectorN2 gtsam::SO< N >::vec ( OptionalJacobian< internal::NSquaredSO< N >(N), dimension H = boost::none) const

Return vectorized rotation matrix in column order. Will use dynamic matrices as intermediate results, but returns a fixed size X and fixed-size Jacobian if dimension is known at compile time.

Definition at line 88 of file SOn-inl.h.

template<int N>
template<int N_ = N, typename = IsFixed<N_>>
static Matrix gtsam::SO< N >::VectorizedGenerators ( )
inlinestatic

Calculate N^2 x dim matrix of vectorized Lie algebra generators for SO(N)

Definition at line 297 of file SOn.h.

template<int N>
template<int N_ = N, typename = IsDynamic<N_>>
static Matrix gtsam::SO< N >::VectorizedGenerators ( size_t  n = 0)
inlinestatic

Calculate n^2 x dim matrix of vectorized Lie algebra generators for SO(n)

Definition at line 309 of file SOn.h.

template<int N>
SO< N >::TangentVector gtsam::SO< N >::Vee ( const MatrixNN X)
static

Inverse of Hat. See note about xi element order in Hat.

Definition at line 35 of file SOn-inl.h.

Friends And Related Function Documentation

template<int N>
friend class boost::serialization::access
friend

Definition at line 329 of file SOn.h.

template<int N>
template<class Archive >
void load ( Archive &  ,
SO< N > &  ,
const unsigned  int 
)
friend
template<int N>
friend class Rot3
friend

Definition at line 330 of file SOn.h.

template<int N>
template<class Archive >
void save ( Archive &  ,
SO< N > &  ,
const unsigned  int 
)
friend
template<int N>
template<class Archive >
void serialize ( Archive &  ,
SO< N > &  ,
const unsigned  int 
)
friend

Member Data Documentation

template<int N>
MatrixNN gtsam::SO< N >::matrix_
protected

Rotation matrix.

Definition at line 60 of file SOn.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:30