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

SE2 using default storage; derived from SE2Base. More...

#include <se2.hpp>

Public Types

using Adjoint = typename Base::Adjoint
 
using Base = SE2Base< SE2< Scalar_, Options > >
 
using HomogeneousPoint = typename Base::HomogeneousPoint
 
using Point = typename Base::Point
 
using Scalar = Scalar_
 
using SO2Member = SO2< Scalar, Options >
 
using Tangent = typename Base::Tangent
 
using Transformation = typename Base::Transformation
 
using TranslationMember = Vector2< Scalar, Options >
 

Public Member Functions

SOPHUS_FUNC Scalardata ()
 
SOPHUS_FUNC Scalar const * data () const
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SOPHUS_FUNC SE2 ()
 
SOPHUS_FUNC SE2 (Scalar const &theta, Point const &translation)
 
SOPHUS_FUNC SE2 (SE2 const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC SE2 (SE2Base< OtherDerived > const &other)
 
template<class OtherDerived , class D >
SOPHUS_FUNC SE2 (SO2Base< OtherDerived > const &so2, Eigen::MatrixBase< D > const &translation)
 
SOPHUS_FUNC SE2 (Transformation const &T)
 
SOPHUS_FUNC SE2 (typename SO2< Scalar >::Transformation const &rotation_matrix, Point const &translation)
 
SOPHUS_FUNC SE2 (Vector2< Scalar > const &complex, Point const &translation)
 
SOPHUS_FUNC SO2Memberso2 ()
 
SOPHUS_FUNC SO2Member const & so2 () 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_theta)
 
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 SE2< Scalarexp (Tangent const &a)
 
template<class S = Scalar>
static SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, SE2fitToSE2 (Matrix3< 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 SE2 rot (Scalar const &x)
 
template<class UniformRandomBitGenerator >
static SE2 sampleUniform (UniformRandomBitGenerator &generator)
 
template<class T0 , class T1 >
static SOPHUS_FUNC SE2 trans (T0 const &x, T1 const &y)
 
static SOPHUS_FUNC SE2 trans (Vector2< Scalar > const &xy)
 
static SOPHUS_FUNC SE2 transX (Scalar const &x)
 
static SOPHUS_FUNC SE2 transY (Scalar const &y)
 
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

SO2Member so2_
 
TranslationMember translation_
 

Detailed Description

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

SE2 using default storage; derived from SE2Base.

Definition at line 11 of file se2.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 376 of file se2.hpp.

◆ Base

template<class Scalar_ , int Options>
using Sophus::SE2< Scalar_, Options >::Base = SE2Base<SE2<Scalar_, Options> >

Definition at line 367 of file se2.hpp.

◆ HomogeneousPoint

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

Definition at line 374 of file se2.hpp.

◆ Point

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

Definition at line 373 of file se2.hpp.

◆ Scalar

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

Definition at line 371 of file se2.hpp.

◆ SO2Member

template<class Scalar_ , int Options>
using Sophus::SE2< Scalar_, Options >::SO2Member = SO2<Scalar, Options>

Definition at line 377 of file se2.hpp.

◆ Tangent

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

Definition at line 375 of file se2.hpp.

◆ Transformation

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

Definition at line 372 of file se2.hpp.

◆ TranslationMember

template<class Scalar_ , int Options>
using Sophus::SE2< Scalar_, Options >::TranslationMember = Vector2<Scalar, Options>

Definition at line 378 of file se2.hpp.

Constructor & Destructor Documentation

◆ SE2() [1/8]

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

Default constructor initializes rigid body motion to the identity.

Definition at line 729 of file se2.hpp.

◆ SE2() [2/8]

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

Copy constructor

◆ SE2() [3/8]

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

Copy-like constructor from OtherDerived

Definition at line 393 of file se2.hpp.

◆ SE2() [4/8]

template<class Scalar_ , int Options>
template<class OtherDerived , class D >
SOPHUS_FUNC Sophus::SE2< Scalar_, Options >::SE2 ( SO2Base< OtherDerived > const &  so2,
Eigen::MatrixBase< D > const &  translation 
)
inline

Constructor from SO3 and translation vector

Definition at line 402 of file se2.hpp.

◆ SE2() [5/8]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::SE2< Scalar_, Options >::SE2 ( typename SO2< Scalar >::Transformation 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 417 of file se2.hpp.

◆ SE2() [6/8]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::SE2< Scalar_, Options >::SE2 ( Scalar const &  theta,
Point const &  translation 
)
inline

Constructor from rotation angle and translation vector.

Definition at line 423 of file se2.hpp.

◆ SE2() [7/8]

template<class Scalar_ , int Options>
SOPHUS_FUNC Sophus::SE2< Scalar_, Options >::SE2 ( Vector2< Scalar > const &  complex,
Point const &  translation 
)
inline

Constructor from complex number and translation vector

Precondition: complex must not be close to zero.

Definition at line 429 of file se2.hpp.

◆ SE2() [8/8]

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

Constructor from 3x3 matrix

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

Definition at line 437 of file se2.hpp.

Member Function Documentation

◆ data() [1/2]

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

This provides unsafe read/write access to internal data. SO(2) is represented by a complex number (two parameters). When using direct write access, the user needs to take care of that the complex number stays normalized.

Definition at line 446 of file se2.hpp.

◆ data() [2/2]

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

Const version of data() above.

so2_ and translation_ are layed out sequentially with no padding

Definition at line 453 of file se2.hpp.

◆ Dx_exp_x()

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

Returns derivative of exp(x) wrt. x.

Definition at line 478 of file se2.hpp.

◆ Dx_exp_x_at_0()

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

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

Definition at line 531 of file se2.hpp.

◆ Dxi_exp_x_matrix_at_0()

template<class Scalar_ , int Options>
static SOPHUS_FUNC Transformation Sophus::SE2< 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 544 of file se2.hpp.

◆ exp()

template<class Scalar_ , int Options>
static SOPHUS_FUNC SE2<Scalar> Sophus::SE2< 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(2).

The first two components of a represent the translational part upsilon in the tangent space of SE(2), 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(2), see below.

Definition at line 560 of file se2.hpp.

◆ fitToSE2()

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

Returns closest SE3 given arbitrary 4x4 matrix.

Definition at line 587 of file se2.hpp.

◆ generator()

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

Returns the ith infinitesimal generators of SE(2).

The infinitesimal generators of SE(2) are:

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

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

Definition at line 612 of file se2.hpp.

◆ hat()

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

hat-operator

It takes in the 3-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^3 -> R^{3x33}, hat(a) = sum_i a_i * G_i (for i=0,1,2)

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

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

Definition at line 633 of file se2.hpp.

◆ lieBracket()

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

Lie bracket

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

[omega_1, omega_2]_se2 := 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(2).

Definition at line 650 of file se2.hpp.

◆ rot()

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

Construct pure rotation.

Definition at line 662 of file se2.hpp.

◆ sampleUniform()

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

Draw uniform sample from SE(2) manifold.

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

Definition at line 671 of file se2.hpp.

◆ so2() [1/2]

template<class Scalar_ , int Options>
SOPHUS_FUNC SO2Member& Sophus::SE2< Scalar_, Options >::so2 ( )
inline

Accessor of SO3

Definition at line 460 of file se2.hpp.

◆ so2() [2/2]

template<class Scalar_ , int Options>
SOPHUS_FUNC SO2Member const& Sophus::SE2< Scalar_, Options >::so2 ( ) const
inline

Mutator of SO3

Definition at line 464 of file se2.hpp.

◆ trans() [1/2]

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

Construct a translation only SE(2) instance.

Definition at line 680 of file se2.hpp.

◆ trans() [2/2]

template<class Scalar_ , int Options>
static SOPHUS_FUNC SE2 Sophus::SE2< Scalar_, Options >::trans ( Vector2< Scalar > const &  xy)
inlinestatic

Definition at line 684 of file se2.hpp.

◆ translation() [1/2]

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

Mutator of translation vector

Definition at line 468 of file se2.hpp.

◆ translation() [2/2]

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

Accessor of translation vector

Definition at line 472 of file se2.hpp.

◆ transX()

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

Construct x-axis translation.

Definition at line 690 of file se2.hpp.

◆ transY()

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

Construct y-axis translation.

Definition at line 696 of file se2.hpp.

◆ vee()

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

vee-operator

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

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

Precondition: Omega must have the following structure:

           |  0 -d  a |
           |  d  0  b |
           |  0  0  0 |

Definition at line 713 of file se2.hpp.

Member Data Documentation

◆ DoF

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

Definition at line 368 of file se2.hpp.

◆ num_parameters

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

Definition at line 369 of file se2.hpp.

◆ so2_

template<class Scalar_ , int Options>
SO2Member Sophus::SE2< Scalar_, Options >::so2_
protected

Definition at line 724 of file se2.hpp.

◆ translation_

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

Definition at line 725 of file se2.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