Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
Sophus::RxSO3< Scalar_, Options > Class Template Reference

RxSO3 using storage; derived from RxSO3Base. More...

#include <rxso3.hpp>

Public Types

using Adjoint = typename Base::Adjoint
 
using Base = RxSO3Base< RxSO3< Scalar_, Options > >
 
using HomogeneousPoint = typename Base::HomogeneousPoint
 
using Point = typename Base::Point
 
using QuaternionMember = Eigen::Quaternion< Scalar, Options >
 
using Scalar = Scalar_
 
using Tangent = typename Base::Tangent
 
using Transformation = typename Base::Transformation
 

Public Member Functions

SOPHUS_FUNC QuaternionMember const & quaternion () const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC RxSO3 ()
 
template<class D >
SOPHUS_FUNC RxSO3 (Eigen::QuaternionBase< D > const &quat)
 
SOPHUS_FUNC RxSO3 (RxSO3 const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC RxSO3 (RxSO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC RxSO3 (Scalar const &scale, SO3< Scalar > const &so3)
 
SOPHUS_FUNC RxSO3 (Scalar const &scale, Transformation const &R)
 
SOPHUS_FUNC RxSO3 (Transformation const &sR)
 

Static Public Member Functions

static SOPHUS_FUNC Transformation Dxi_exp_x_matrix_at_0 (int i)
 
static SOPHUS_FUNC RxSO3< Scalarexp (Tangent const &a)
 
static SOPHUS_FUNC RxSO3< ScalarexpAndTheta (Tangent const &a, Scalar *theta)
 
static SOPHUS_FUNC Transformation generator (int i)
 
static SOPHUS_FUNC Transformation hat (Tangent const &a)
 
static SOPHUS_FUNC Tangent lieBracket (Tangent const &a, Tangent const &b)
 
template<class UniformRandomBitGenerator >
static RxSO3 sampleUniform (UniformRandomBitGenerator &generator)
 
static SOPHUS_FUNC Tangent vee (Transformation const &Omega)
 

Protected Member Functions

SOPHUS_FUNC QuaternionMemberquaternion_nonconst ()
 

Protected Attributes

QuaternionMember quaternion_
 

Friends

class RxSO3Base< RxSO3< Scalar_, Options > >
 Base is friend so quaternion_nonconst can be accessed from Base. More...
 

Detailed Description

template<class Scalar_, int Options>
class Sophus::RxSO3< Scalar_, Options >

RxSO3 using storage; derived from RxSO3Base.

Definition at line 11 of file rxso3.hpp.

Member Typedef Documentation

◆ Adjoint

template<class Scalar_ , int Options>
using Sophus::RxSO3< Scalar_, Options >::Adjoint = typename Base::Adjoint

Definition at line 419 of file rxso3.hpp.

◆ Base

template<class Scalar_ , int Options>
using Sophus::RxSO3< Scalar_, Options >::Base = RxSO3Base<RxSO3<Scalar_, Options> >

Definition at line 413 of file rxso3.hpp.

◆ HomogeneousPoint

template<class Scalar_ , int Options>
using Sophus::RxSO3< Scalar_, Options >::HomogeneousPoint = typename Base::HomogeneousPoint

Definition at line 417 of file rxso3.hpp.

◆ Point

template<class Scalar_ , int Options>
using Sophus::RxSO3< Scalar_, Options >::Point = typename Base::Point

Definition at line 416 of file rxso3.hpp.

◆ QuaternionMember

template<class Scalar_ , int Options>
using Sophus::RxSO3< Scalar_, Options >::QuaternionMember = Eigen::Quaternion<Scalar, Options>

Definition at line 420 of file rxso3.hpp.

◆ Scalar

template<class Scalar_ , int Options>
using Sophus::RxSO3< Scalar_, Options >::Scalar = Scalar_

Definition at line 414 of file rxso3.hpp.

◆ Tangent

template<class Scalar_ , int Options>
using Sophus::RxSO3< Scalar_, Options >::Tangent = typename Base::Tangent

Definition at line 418 of file rxso3.hpp.

◆ Transformation

template<class Scalar_ , int Options>
using Sophus::RxSO3< Scalar_, Options >::Transformation = typename Base::Transformation

Definition at line 415 of file rxso3.hpp.

Constructor & Destructor Documentation

◆ RxSO3() [1/7]

template<class Scalar_ , int Options>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC Sophus::RxSO3< Scalar_, Options >::RxSO3 ( )
inline

Default constructor initializes quaternion to identity rotation and scale to 1.

Definition at line 430 of file rxso3.hpp.

◆ RxSO3() [2/7]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::RxSO3< Scalar_, Options >::RxSO3 ( RxSO3< Scalar_, Options > const &  other)
default

Copy constructor

◆ RxSO3() [3/7]

template<class Scalar_ , int Options>
template<class OtherDerived >
SOPHUS_FUNC Sophus::RxSO3< Scalar_, Options >::RxSO3 ( RxSO3Base< OtherDerived > const &  other)
inline

Copy-like constructor from OtherDerived

Definition at line 440 of file rxso3.hpp.

◆ RxSO3() [4/7]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::RxSO3< Scalar_, Options >::RxSO3 ( Transformation const &  sR)
inlineexplicit

Constructor from scaled rotation matrix

Precondition: rotation matrix need to be scaled orthogonal with determinant of s^3.

Definition at line 448 of file rxso3.hpp.

◆ RxSO3() [5/7]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::RxSO3< Scalar_, Options >::RxSO3 ( Scalar const &  scale,
Transformation const &  R 
)
inline

Constructor from scale factor and rotation matrix R.

Precondition: Rotation matrix R must to be orthogonal with determinant of 1 and scale must not be close to zero.

Definition at line 457 of file rxso3.hpp.

◆ RxSO3() [6/7]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::RxSO3< Scalar_, Options >::RxSO3 ( Scalar const &  scale,
SO3< Scalar > const &  so3 
)
inline

Constructor from scale factor and SO3

Precondition: scale must not to be close to zero.

Definition at line 469 of file rxso3.hpp.

◆ RxSO3() [7/7]

template<class Scalar_ , int Options>
template<class D >
SOPHUS_FUNC Sophus::RxSO3< Scalar_, Options >::RxSO3 ( Eigen::QuaternionBase< D > const &  quat)
inlineexplicit

Constructor from quaternion

Precondition: quaternion must not be close to zero.

Definition at line 482 of file rxso3.hpp.

Member Function Documentation

◆ Dxi_exp_x_matrix_at_0()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Transformation Sophus::RxSO3< Scalar_, Options >::Dxi_exp_x_matrix_at_0 ( int  i)
inlinestatic

Returns derivative of exp(x).matrix() wrt. x_i at x=0.

Definition at line 496 of file rxso3.hpp.

◆ exp()

template<class Scalar_ , int Options>
static SOPHUS_FUNC RxSO3<Scalar> Sophus::RxSO3< Scalar_, Options >::exp ( Tangent const &  a)
inlinestatic

Group exponential

This functions takes in an element of tangent space (= rotation 3-vector plus logarithm of scale) and returns the corresponding element of the group RxSO3.

To be more specific, thixs function computes expmat(hat(omega)) with expmat(.) being the matrix exponential and hat(.) being the hat()-operator of RSO3.

Definition at line 509 of file rxso3.hpp.

◆ expAndTheta()

template<class Scalar_ , int Options>
static SOPHUS_FUNC RxSO3<Scalar> Sophus::RxSO3< Scalar_, Options >::expAndTheta ( Tangent const &  a,
Scalar theta 
)
inlinestatic

As above, but also returns theta = |omega| as out-parameter.

Precondition: theta must not be nullptr.

Definition at line 518 of file rxso3.hpp.

◆ generator()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Transformation Sophus::RxSO3< Scalar_, Options >::generator ( int  i)
inlinestatic

Returns the ith infinitesimal generators of R+ x SO(3).

The infinitesimal generators of RxSO3 are:

| 0 0 0 |
G_0 = | 0 0 -1 |
| 0 1 0 |
| 0 0 1 |
G_1 = | 0 0 0 |
| -1 0 0 |
| 0 -1 0 |
G_2 = | 1 0 0 |
| 0 0 0 |
| 1 0 0 |
G_2 = | 0 1 0 |
| 0 0 1 |

Precondition: i must be 0, 1, 2 or 3.

Definition at line 557 of file rxso3.hpp.

◆ hat()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Transformation Sophus::RxSO3< Scalar_, Options >::hat ( Tangent const &  a)
inlinestatic

hat-operator

It takes in the 4-vector representation a (= rotation vector plus logarithm of scale) and returns the corresponding matrix representation of Lie algebra element.

Formally, the hat()-operator of RxSO3 is defined as

hat(.): R^4 -> R^{3x3}, hat(a) = sum_i a_i * G_i (for i=0,1,2,3)

with G_i being the ith infinitesimal generator of RxSO3.

The corresponding inverse is the vee()-operator, see below.

Definition at line 579 of file rxso3.hpp.

◆ lieBracket()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Tangent Sophus::RxSO3< Scalar_, Options >::lieBracket ( Tangent const &  a,
Tangent const &  b 
)
inlinestatic

Lie bracket

It computes the Lie bracket of RxSO(3). To be more specific, it computes

[omega_1, omega_2]_rxso3 := vee([hat(omega_1), hat(omega_2)])

with [A,B] := AB-BA being the matrix commutator, hat(.) the hat()-operator and vee(.) the vee()-operator of RxSO3.

Definition at line 598 of file rxso3.hpp.

◆ quaternion()

template<class Scalar_ , int Options>
SOPHUS_FUNC QuaternionMember const& Sophus::RxSO3< Scalar_, Options >::quaternion ( ) const
inline

Accessor of quaternion.

Definition at line 492 of file rxso3.hpp.

◆ quaternion_nonconst()

template<class Scalar_ , int Options>
SOPHUS_FUNC QuaternionMember& Sophus::RxSO3< Scalar_, Options >::quaternion_nonconst ( )
inlineprotected

Definition at line 639 of file rxso3.hpp.

◆ sampleUniform()

template<class Scalar_ , int Options>
template<class UniformRandomBitGenerator >
static RxSO3 Sophus::RxSO3< Scalar_, Options >::sampleUniform ( UniformRandomBitGenerator &  generator)
inlinestatic

Draw uniform sample from RxSO(3) manifold.

The scale factor is drawn uniformly in log2-space from [-1, 1], hence the scale is in [0.5, 2].

Definition at line 613 of file rxso3.hpp.

◆ vee()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Tangent Sophus::RxSO3< Scalar_, Options >::vee ( Transformation const &  Omega)
inlinestatic

vee-operator

It takes the 3x3-matrix representation Omega and maps it to the corresponding vector representation of Lie algebra.

This is the inverse of the hat()-operator, see above.

Precondition: Omega must have the following structure:

           |  d -c  b |
           |  c  d -a |
           | -b  a  d |

Definition at line 633 of file rxso3.hpp.

Friends And Related Function Documentation

◆ RxSO3Base< RxSO3< Scalar_, Options > >

template<class Scalar_ , int Options>
friend class RxSO3Base< RxSO3< Scalar_, Options > >
friend

Base is friend so quaternion_nonconst can be accessed from Base.

Definition at line 423 of file rxso3.hpp.

Member Data Documentation

◆ quaternion_

template<class Scalar_ , int Options>
QuaternionMember Sophus::RxSO3< Scalar_, Options >::quaternion_
protected

Definition at line 641 of file rxso3.hpp.


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


sophus
Author(s): Hauke Strasdat
autogenerated on Wed Mar 2 2022 01:01:48