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

SO3 using default storage; derived from SO3Base. More...

#include <so3.hpp>

Public Types

using Adjoint = typename Base::Adjoint
 
using Base = SO3Base< SO3< 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

EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC SO3 ()
 
template<class D >
SOPHUS_FUNC SO3 (Eigen::QuaternionBase< D > const &quat)
 
SOPHUS_FUNC SO3 (SO3 const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC SO3 (SO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC SO3 (Transformation const &R)
 
SOPHUS_FUNC QuaternionMember const & unit_quaternion () const
 

Static Public Member Functions

static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoFDx_exp_x (Tangent const &omega)
 
static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoFDx_exp_x_at_0 ()
 
static SOPHUS_FUNC Transformation Dxi_exp_x_matrix_at_0 (int i)
 
static SOPHUS_FUNC SO3< Scalarexp (Tangent const &omega)
 
static SOPHUS_FUNC SO3< ScalarexpAndTheta (Tangent const &omega, Scalar *theta)
 
template<class S = Scalar>
static SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, SO3fitToSO3 (Transformation const &R)
 
static SOPHUS_FUNC Transformation generator (int i)
 
static SOPHUS_FUNC Transformation hat (Tangent const &omega)
 
static SOPHUS_FUNC Tangent lieBracket (Tangent const &omega1, Tangent const &omega2)
 
static SOPHUS_FUNC SO3 rotX (Scalar const &x)
 
static SOPHUS_FUNC SO3 rotY (Scalar const &y)
 
static SOPHUS_FUNC SO3 rotZ (Scalar const &z)
 
template<class UniformRandomBitGenerator >
static SO3 sampleUniform (UniformRandomBitGenerator &generator)
 
static SOPHUS_FUNC Tangent vee (Transformation const &Omega)
 

Static Public Attributes

static constexpr int DoF = Base::DoF
 
static constexpr int num_parameters = Base::num_parameters
 

Protected Member Functions

SOPHUS_FUNC QuaternionMemberunit_quaternion_nonconst ()
 

Protected Attributes

QuaternionMember unit_quaternion_
 

Friends

class SO3Base< SO3< Scalar, Options > >
 

Detailed Description

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

SO3 using default storage; derived from SO3Base.

Definition at line 19 of file so3.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 437 of file so3.hpp.

◆ Base

template<class Scalar_ , int Options>
using Sophus::SO3< Scalar_, Options >::Base = SO3Base<SO3<Scalar_, Options> >

Definition at line 428 of file so3.hpp.

◆ HomogeneousPoint

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

Definition at line 435 of file so3.hpp.

◆ Point

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

Definition at line 434 of file so3.hpp.

◆ QuaternionMember

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

Definition at line 438 of file so3.hpp.

◆ Scalar

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

Definition at line 432 of file so3.hpp.

◆ Tangent

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

Definition at line 436 of file so3.hpp.

◆ Transformation

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

Definition at line 433 of file so3.hpp.

Constructor & Destructor Documentation

◆ SO3() [1/5]

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

Default constructor initializes unit quaternion to identity rotation.

Definition at line 448 of file so3.hpp.

◆ SO3() [2/5]

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

Copy constructor

◆ SO3() [3/5]

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

Copy-like constructor from OtherDerived.

Definition at line 458 of file so3.hpp.

◆ SO3() [4/5]

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

Constructor from rotation matrix

Precondition: rotation matrix needs to be orthogonal with determinant of 1.

Definition at line 466 of file so3.hpp.

◆ SO3() [5/5]

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

Constructor from quaternion

Precondition: quaternion must not be close to zero.

Definition at line 478 of file so3.hpp.

Member Function Documentation

◆ Dx_exp_x()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Sophus::Matrix<Scalar, num_parameters, DoF> Sophus::SO3< Scalar_, Options >::Dx_exp_x ( Tangent const &  omega)
inlinestatic

Returns derivative of exp(x) wrt. x.

Definition at line 494 of file so3.hpp.

◆ Dx_exp_x_at_0()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Sophus::Matrix<Scalar, num_parameters, DoF> Sophus::SO3< Scalar_, Options >::Dx_exp_x_at_0 ( )
inlinestatic

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

Definition at line 545 of file so3.hpp.

◆ Dxi_exp_x_matrix_at_0()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Transformation Sophus::SO3< 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 558 of file so3.hpp.

◆ exp()

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

Group exponential

This functions takes in an element of tangent space (= rotation vector omega) and returns the corresponding element of the group SO(3).

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

Definition at line 571 of file so3.hpp.

◆ expAndTheta()

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

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

Precondition: theta must not be nullptr.

Definition at line 580 of file so3.hpp.

◆ fitToSO3()

template<class Scalar_ , int Options>
template<class S = Scalar>
static SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, SO3> Sophus::SO3< Scalar_, Options >::fitToSO3 ( Transformation const &  R)
inlinestatic

Returns closest SO3 given arbitrary 3x3 matrix.

Definition at line 622 of file so3.hpp.

◆ generator()

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

Returns the ith infinitesimal generators of SO(3).

The infinitesimal generators of SO(3) 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 |

Precondition: i must be 0, 1 or 2.

Definition at line 646 of file so3.hpp.

◆ hat()

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

hat-operator

It takes in the 3-vector representation omega (= rotation vector) and returns the corresponding matrix representation of Lie algebra element.

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

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

with G_i being the ith infinitesimal generator of SO(3).

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

Definition at line 668 of file so3.hpp.

◆ lieBracket()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Tangent Sophus::SO3< Scalar_, Options >::lieBracket ( Tangent const &  omega1,
Tangent const &  omega2 
)
inlinestatic

Lie bracket

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

[omega_1, omega_2]_so3 := 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 SO3.

For the Lie algebra so3, the Lie bracket is simply the cross product:

[omega_1, omega_2]_so3 = omega_1 x omega_2.

Definition at line 692 of file so3.hpp.

◆ rotX()

template<class Scalar_ , int Options>
static SOPHUS_FUNC SO3 Sophus::SO3< Scalar_, Options >::rotX ( Scalar const &  x)
inlinestatic

Construct x-axis rotation.

Definition at line 699 of file so3.hpp.

◆ rotY()

template<class Scalar_ , int Options>
static SOPHUS_FUNC SO3 Sophus::SO3< Scalar_, Options >::rotY ( Scalar const &  y)
inlinestatic

Construct y-axis rotation.

Definition at line 705 of file so3.hpp.

◆ rotZ()

template<class Scalar_ , int Options>
static SOPHUS_FUNC SO3 Sophus::SO3< Scalar_, Options >::rotZ ( Scalar const &  z)
inlinestatic

Construct z-axis rotation.

Definition at line 711 of file so3.hpp.

◆ sampleUniform()

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

Draw uniform sample from SO(3) manifold.

Definition at line 718 of file so3.hpp.

◆ unit_quaternion()

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

Accessor of unit quaternion.

Definition at line 488 of file so3.hpp.

◆ unit_quaternion_nonconst()

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

Mutator of unit_quaternion is protected to ensure class invariant.

Definition at line 756 of file so3.hpp.

◆ vee()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Tangent Sophus::SO3< 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:

           |  0 -c  b |
           |  c  0 -a |
           | -b  a  0 |

Definition at line 749 of file so3.hpp.

Friends And Related Function Documentation

◆ SO3Base< SO3< Scalar, Options > >

template<class Scalar_ , int Options>
friend class SO3Base< SO3< Scalar, Options > >
friend

Base is friend so unit_quaternion_nonconst can be accessed from Base.

Definition at line 442 of file so3.hpp.

Member Data Documentation

◆ DoF

template<class Scalar_ , int Options>
constexpr int Sophus::SO3< Scalar_, Options >::DoF = Base::DoF
staticconstexpr

Definition at line 429 of file so3.hpp.

◆ num_parameters

template<class Scalar_ , int Options>
constexpr int Sophus::SO3< Scalar_, Options >::num_parameters = Base::num_parameters
staticconstexpr

Definition at line 430 of file so3.hpp.

◆ unit_quaternion_

template<class Scalar_ , int Options>
QuaternionMember Sophus::SO3< Scalar_, Options >::unit_quaternion_
protected

Definition at line 760 of file so3.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