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
|
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.
|
|
static size_t | Dimension (size_t n) |
|
static size_t | AmbientDim (size_t d) |
|
static MatrixNN | Hat (const TangentVector &xi) |
| Hat operator creates Lie algebra element corresponding to d-vector, where d is the dimensionality of the manifold. More...
|
|
static void | Hat (const Vector &xi, Eigen::Ref< MatrixNN > X) |
| In-place version of Hat (see details there), implements recursion.
|
|
static TangentVector | Vee (const MatrixNN &X) |
| Inverse of Hat. See note about xi element order in Hat.
|
|
template<int N_ = N, typename = IsDynamic<N_>> |
static MatrixDD | IdentityJacobian (size_t n) |
|
|
template<int N_ = N, typename = IsFixed<N_>> |
| SO () |
| Construct SO<N> identity for N >= 2.
|
|
template<int N_ = N, typename = IsDynamic<N_>> |
| SO (size_t n=0) |
| Construct SO<N> identity for N == Eigen::Dynamic.
|
|
template<typename Derived > |
| SO (const Eigen::MatrixBase< Derived > &R) |
| Constructor from Eigen Matrix, dynamic version.
|
|
template<int M, int N_ = N, typename = IsDynamic<N_>> |
| SO (const SO< M > &R) |
| Construct dynamic SO(n) from Fixed SO<M>
|
|
template<int N_ = N, typename = IsSO3<N_>> |
| SO (const Eigen::AngleAxisd &angleAxis) |
| Constructor from AngleAxisd.
|
|
template<typename Derived > |
static SO | FromMatrix (const Eigen::MatrixBase< Derived > &R) |
| Named constructor from Eigen Matrix.
|
|
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.
|
|
static SO | AxisAngle (const Vector3 &axis, double theta) |
| Constructor from axis and angle. Only defined for SO3.
|
|
static SO | ClosestTo (const MatrixNN &M) |
| Named constructor that finds SO(n) matrix closest to M in Frobenius norm, currently only defined for SO3.
|
|
static SO | ChordalMean (const std::vector< SO > &rotations) |
| Named constructor that finds chordal mean = argmin_R \sum sqr(|R-R_i|_F), currently only defined for SO3.
|
|
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.
|
|
template<int N_ = N, typename = IsFixed<N_>> |
static SO | Random (std::mt19937 &rng) |
| Random SO(N) element (no big claims about uniformity)
|
|
|
MatrixDD | AdjointMap () const |
| Adjoint map.
|
|
static SO | Expmap (const TangentVector &omega, ChartJacobian H=boost::none) |
| Exponential map at identity - create a rotation from canonical coordinates.
|
|
static MatrixDD | ExpmapDerivative (const TangentVector &omega) |
| Derivative of Expmap, currently only defined for SO3.
|
|
static TangentVector | Logmap (const SO &R, ChartJacobian H=boost::none) |
| Log map at identity - returns the canonical coordinates of this rotation.
|
|
static MatrixDD | LogmapDerivative (const TangentVector &omega) |
| Derivative of Logmap, currently only defined for SO3.
|
|
|
|
const MatrixNN & | matrix () const |
| Return matrix.
|
|
size_t | rows () const |
|
size_t | cols () const |
|
|
void | print (const std::string &s=std::string()) const |
|
bool | equals (const SO &other, double tol) const |
|
const SO< N > & | derived () const |
|
SO< N > | compose (const SO< N > &g) const |
|
SO< N > | compose (const SO< N > &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
|
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SO< N > | between (const SO< N > &g) const |
|
SO< N > | between (const SO< N > &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
|
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SO< N > | inverse (ChartJacobian H) const |
|
SO< N > | expmap (const TangentVector &v) const |
| expmap as required by manifold concept Applies exponential map to v and composes with *this
|
|
SO< N > | expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| expmap with optional derivatives
|
|
TangentVector | logmap (const SO< N > &g) const |
| logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g
|
|
TangentVector | logmap (const SO< N > &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| logmap with optional derivatives
|
|
SO< N > | retract (const TangentVector &v) const |
| retract as required by manifold concept: applies v at *this
|
|
SO< N > | retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| retract with optional derivatives
|
|
TangentVector | localCoordinates (const SO< N > &g) const |
| localCoordinates as required by manifold concept: finds tangent vector between *this and g
|
|
TangentVector | localCoordinates (const SO< N > &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
| localCoordinates with optional derivatives
|
|
|
enum | { dimension = internal::DimensionSO(N)
} |
|
using | MatrixNN = Eigen::Matrix< double, N, N > |
|
using | VectorN2 = Eigen::Matrix< double, internal::NSquaredSO(N), 1 > |
|
using | MatrixDD = Eigen::Matrix< double, dimension, dimension > |
|
enum | |
|
typedef OptionalJacobian< N, N > | ChartJacobian |
|
typedef Eigen::Matrix< double, N, N > | Jacobian |
|
typedef Eigen::Matrix< double, N, 1 > | TangentVector |
|
|
static SO< N > | Retract (const TangentVector &v) |
| Retract at origin: possible in Lie group because it has an identity.
|
|
static SO< N > | Retract (const TangentVector &v, ChartJacobian H) |
| Retract at origin with optional derivative.
|
|
static TangentVector | LocalCoordinates (const SO< N > &g) |
| LocalCoordinates at origin: possible in Lie group because it has an identity.
|
|
static TangentVector | LocalCoordinates (const SO< N > &g, ChartJacobian H) |
| LocalCoordinates at origin with optional derivative.
|
|
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).