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

SE3 using default storage; derived from SE3Base. More...

#include <se3.hpp>

Public Types

using Adjoint = typename Base::Adjoint
 
using HomogeneousPoint = typename Base::HomogeneousPoint
 
using Point = typename Base::Point
 
using Scalar = Scalar_
 
using SO3Member = SO3< Scalar, Options >
 
using Tangent = typename Base::Tangent
 
using Transformation = typename Base::Transformation
 
using TranslationMember = Vector3< Scalar, Options >
 

Public Member Functions

SOPHUS_FUNC Scalardata ()
 
SOPHUS_FUNC Scalar const * data () const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC SE3 ()
 
SOPHUS_FUNC SE3 (Eigen::Quaternion< Scalar > const &quaternion, Point const &translation)
 
SOPHUS_FUNC SE3 (Matrix3< Scalar > const &rotation_matrix, Point const &translation)
 
SOPHUS_FUNC SE3 (Matrix4< Scalar > const &T)
 
SOPHUS_FUNC SE3 (SE3 const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC SE3 (SE3Base< OtherDerived > const &other)
 
template<class OtherDerived , class D >
SOPHUS_FUNC SE3 (SO3Base< OtherDerived > const &so3, Eigen::MatrixBase< D > const &translation)
 
SOPHUS_FUNC SO3Memberso3 ()
 
SOPHUS_FUNC SO3Member const & so3 () const
 
SOPHUS_FUNC TranslationMembertranslation ()
 
SOPHUS_FUNC TranslationMember const & translation () const
 

Static Public Member Functions

static SOPHUS_FUNC Sophus::Matrix< Scalar, num_parameters, DoFDx_exp_x (Tangent const &upsilon_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 SE3< Scalarexp (Tangent const &a)
 
template<class S = Scalar>
static SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, SE3fitToSE3 (Matrix4< Scalar > const &T)
 
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)
 
static SOPHUS_FUNC SE3 rotX (Scalar const &x)
 
static SOPHUS_FUNC SE3 rotY (Scalar const &y)
 
static SOPHUS_FUNC SE3 rotZ (Scalar const &z)
 
template<class UniformRandomBitGenerator >
static SE3 sampleUniform (UniformRandomBitGenerator &generator)
 
template<class T0 , class T1 , class T2 >
static SOPHUS_FUNC SE3 trans (T0 const &x, T1 const &y, T2 const &z)
 
static SOPHUS_FUNC SE3 trans (Vector3< Scalar > const &xyz)
 
static SOPHUS_FUNC SE3 transX (Scalar const &x)
 
static SOPHUS_FUNC SE3 transY (Scalar const &y)
 
static SOPHUS_FUNC SE3 transZ (Scalar const &z)
 
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 Attributes

SO3Member so3_
 
TranslationMember translation_
 

Private Types

using Base = SE3Base< SE3< Scalar_, Options > >
 

Detailed Description

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

SE3 using default storage; derived from SE3Base.

Definition at line 11 of file se3.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 442 of file se3.hpp.

◆ Base

template<class Scalar_ , int Options>
using Sophus::SE3< Scalar_, Options >::Base = SE3Base<SE3<Scalar_, Options> >
private

Definition at line 431 of file se3.hpp.

◆ HomogeneousPoint

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

Definition at line 440 of file se3.hpp.

◆ Point

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

Definition at line 439 of file se3.hpp.

◆ Scalar

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

Definition at line 437 of file se3.hpp.

◆ SO3Member

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

Definition at line 443 of file se3.hpp.

◆ Tangent

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

Definition at line 441 of file se3.hpp.

◆ Transformation

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

Definition at line 438 of file se3.hpp.

◆ TranslationMember

template<class Scalar_ , int Options>
using Sophus::SE3< Scalar_, Options >::TranslationMember = Vector3<Scalar, Options>

Definition at line 444 of file se3.hpp.

Constructor & Destructor Documentation

◆ SE3() [1/7]

template<class Scalar , int Options>
Sophus::SE3< Scalar, Options >::SE3

Default constructor initializes rigid body motion to the identity.

Definition at line 972 of file se3.hpp.

◆ SE3() [2/7]

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

Copy constructor

◆ SE3() [3/7]

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

Copy-like constructor from OtherDerived.

Definition at line 459 of file se3.hpp.

◆ SE3() [4/7]

template<class Scalar_ , int Options>
template<class OtherDerived , class D >
SOPHUS_FUNC Sophus::SE3< Scalar_, Options >::SE3 ( SO3Base< OtherDerived > const &  so3,
Eigen::MatrixBase< D > const &  translation 
)
inline

Constructor from SO3 and translation vector

Definition at line 468 of file se3.hpp.

◆ SE3() [5/7]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::SE3< Scalar_, Options >::SE3 ( Matrix3< Scalar > const &  rotation_matrix,
Point const &  translation 
)
inline

Constructor from rotation matrix and translation vector

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

Definition at line 483 of file se3.hpp.

◆ SE3() [6/7]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::SE3< Scalar_, Options >::SE3 ( Eigen::Quaternion< Scalar > const &  quaternion,
Point const &  translation 
)
inline

Constructor from quaternion and translation vector.

Precondition: quaternion must not be close to zero.

Definition at line 490 of file se3.hpp.

◆ SE3() [7/7]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::SE3< Scalar_, Options >::SE3 ( Matrix4< Scalar > const &  T)
inlineexplicit

Constructor from 4x4 matrix

Precondition: Rotation matrix needs to be orthogonal with determinant of 1. The last row must be (0, 0, 0, 1).

Definition at line 499 of file se3.hpp.

Member Function Documentation

◆ data() [1/2]

template<class Scalar_ , int Options>
SOPHUS_FUNC Scalar* Sophus::SE3< Scalar_, Options >::data ( )
inline

This provides unsafe read/write access to internal data. SO(3) is represented by an Eigen::Quaternion (four parameters). When using direct write access, the user needs to take care of that the quaternion stays normalized.

Definition at line 513 of file se3.hpp.

◆ data() [2/2]

template<class Scalar_ , int Options>
SOPHUS_FUNC Scalar const* Sophus::SE3< Scalar_, Options >::data ( ) const
inline

Const version of data() above.

Definition at line 520 of file se3.hpp.

◆ Dx_exp_x()

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

Returns derivative of exp(x) wrt. x.

clang-format off

clang-format on

Definition at line 545 of file se3.hpp.

◆ Dx_exp_x_at_0()

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

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

Definition at line 728 of file se3.hpp.

◆ Dxi_exp_x_matrix_at_0()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Transformation Sophus::SE3< 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 747 of file se3.hpp.

◆ exp()

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

Group exponential

This functions takes in an element of tangent space (= twist a) and returns the corresponding element of the group SE(3).

The first three components of a represent the translational part upsilon in the tangent space of SE(3), while the last three components of a represents the rotation vector omega. To be more specific, this function computes expmat(hat(a)) with expmat(.) being the matrix exponential and hat(.) the hat-operator of SE(3), see below.

Note: That is an accurate expansion!

Definition at line 763 of file se3.hpp.

◆ fitToSE3()

template<class Scalar_ , int Options>
template<class S = Scalar>
static SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, SE3> Sophus::SE3< Scalar_, Options >::fitToSE3 ( Matrix4< Scalar > const &  T)
inlinestatic

Returns closest SE3 given arbirary 4x4 matrix.

Definition at line 790 of file se3.hpp.

◆ generator()

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

Returns the ith infinitesimal generators of SE(3).

The infinitesimal generators of SE(3) are:

| 0 0 0 1 |
G_0 = | 0 0 0 0 |
| 0 0 0 0 |
| 0 0 0 0 |
| 0 0 0 0 |
G_1 = | 0 0 0 1 |
| 0 0 0 0 |
| 0 0 0 0 |
| 0 0 0 0 |
G_2 = | 0 0 0 0 |
| 0 0 0 1 |
| 0 0 0 0 |
| 0 0 0 0 |
G_3 = | 0 0 -1 0 |
| 0 1 0 0 |
| 0 0 0 0 |
| 0 0 1 0 |
G_4 = | 0 0 0 0 |
| -1 0 0 0 |
| 0 0 0 0 |
| 0 -1 0 0 |
G_5 = | 1 0 0 0 |
| 0 0 0 0 |
| 0 0 0 0 |

Precondition: i must be in [0, 5].

Definition at line 833 of file se3.hpp.

◆ hat()

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

hat-operator

It takes in the 6-vector representation (= twist) and returns the corresponding matrix representation of Lie algebra element.

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

hat(.): R^6 -> R^{4x4}, hat(a) = sum_i a_i * G_i (for i=0,...,5)

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

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

Definition at line 854 of file se3.hpp.

◆ lieBracket()

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

Lie bracket

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

[omega_1, omega_2]_se3 := 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 SE(3).

Definition at line 872 of file se3.hpp.

◆ rotX()

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

Construct x-axis rotation.

Definition at line 887 of file se3.hpp.

◆ rotY()

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

Construct y-axis rotation.

Definition at line 893 of file se3.hpp.

◆ rotZ()

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

Construct z-axis rotation.

Definition at line 899 of file se3.hpp.

◆ sampleUniform()

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

Draw uniform sample from SE(3) manifold.

Translations are drawn component-wise from the range [-1, 1].

Definition at line 908 of file se3.hpp.

◆ so3() [1/2]

template<class Scalar_ , int Options>
SOPHUS_FUNC SO3Member& Sophus::SE3< Scalar_, Options >::so3 ( )
inline

Accessor of SO3

Definition at line 527 of file se3.hpp.

◆ so3() [2/2]

template<class Scalar_ , int Options>
SOPHUS_FUNC SO3Member const& Sophus::SE3< Scalar_, Options >::so3 ( ) const
inline

Mutator of SO3

Definition at line 531 of file se3.hpp.

◆ trans() [1/2]

template<class Scalar_ , int Options>
template<class T0 , class T1 , class T2 >
static SOPHUS_FUNC SE3 Sophus::SE3< Scalar_, Options >::trans ( T0 const &  x,
T1 const &  y,
T2 const &  z 
)
inlinestatic

Construct a translation only SE3 instance.

Definition at line 918 of file se3.hpp.

◆ trans() [2/2]

template<class Scalar_ , int Options>
static SOPHUS_FUNC SE3 Sophus::SE3< Scalar_, Options >::trans ( Vector3< Scalar > const &  xyz)
inlinestatic

Definition at line 922 of file se3.hpp.

◆ translation() [1/2]

template<class Scalar_ , int Options>
SOPHUS_FUNC TranslationMember& Sophus::SE3< Scalar_, Options >::translation ( )
inline

Mutator of translation vector

Definition at line 535 of file se3.hpp.

◆ translation() [2/2]

template<class Scalar_ , int Options>
SOPHUS_FUNC TranslationMember const& Sophus::SE3< Scalar_, Options >::translation ( ) const
inline

Accessor of translation vector

Definition at line 539 of file se3.hpp.

◆ transX()

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

Construct x-axis translation.

Definition at line 928 of file se3.hpp.

◆ transY()

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

Construct y-axis translation.

Definition at line 934 of file se3.hpp.

◆ transZ()

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

Construct z-axis translation.

Definition at line 940 of file se3.hpp.

◆ vee()

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

vee-operator

It takes 4x4-matrix representation Omega and maps it to the corresponding 6-vector representation of Lie algebra.

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

Precondition: Omega must have the following structure:

           |  0 -f  e  a |
           |  f  0 -d  b |
           | -e  d  0  c
           |  0  0  0  0 | .

Definition at line 958 of file se3.hpp.

Member Data Documentation

◆ DoF

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

Definition at line 434 of file se3.hpp.

◆ num_parameters

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

Definition at line 435 of file se3.hpp.

◆ so3_

template<class Scalar_ , int Options>
SO3Member Sophus::SE3< Scalar_, Options >::so3_
protected

Definition at line 967 of file se3.hpp.

◆ translation_

template<class Scalar_ , int Options>
TranslationMember Sophus::SE3< Scalar_, Options >::translation_
protected

Definition at line 968 of file se3.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