Public Types | Public Member Functions | Static Public Attributes | List of all members
Sophus::SE2Base< Derived > Class Template Reference

#include <se2.hpp>

Public Types

using Adjoint = Matrix< Scalar, DoF, DoF >
 
using HomogeneousPoint = Vector3< Scalar >
 
template<typename HPointDerived >
using HomogeneousPointProduct = Vector3< ReturnScalar< HPointDerived > >
 
using Line = ParametrizedLine2< Scalar >
 
using Point = Vector2< Scalar >
 
template<typename PointDerived >
using PointProduct = Vector2< ReturnScalar< PointDerived > >
 
template<typename OtherDerived >
using ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType
 
using Scalar = typename Eigen::internal::traits< Derived >::Scalar
 
template<typename OtherDerived >
using SE2Product = SE2< ReturnScalar< OtherDerived > >
 
using SO2Type = typename Eigen::internal::traits< Derived >::SO2Type
 
using Tangent = Vector< Scalar, DoF >
 
using Transformation = Matrix< Scalar, N, N >
 
using TranslationType = typename Eigen::internal::traits< Derived >::TranslationType
 

Public Member Functions

SOPHUS_FUNC Adjoint Adj () const
 
template<class NewScalarType >
SOPHUS_FUNC SE2< NewScalarType > cast () const
 
SOPHUS_FUNC Matrix< Scalar, num_parameters, DoFDx_this_mul_exp_x_at_0 () const
 
SOPHUS_FUNC SE2< Scalarinverse () const
 
SOPHUS_FUNC Tangent log () const
 
SOPHUS_FUNC Transformation matrix () const
 
SOPHUS_FUNC Matrix< Scalar, 2, 3 > matrix2x3 () const
 
SOPHUS_FUNC void normalize ()
 
template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 3>::value>::type>
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const
 
template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 2>::value>::type>
SOPHUS_FUNC PointProduct< PointDerived > operator* (Eigen::MatrixBase< PointDerived > const &p) const
 
SOPHUS_FUNC Line operator* (Line const &l) const
 
template<typename OtherDerived >
SOPHUS_FUNC SE2Product< OtherDerived > operator* (SE2Base< OtherDerived > const &other) const
 
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC SE2Base< Derived > & operator*= (SE2Base< OtherDerived > const &other)
 
SOPHUS_FUNC SE2Baseoperator= (SE2Base const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC SE2Base< Derived > & operator= (SE2Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sophus::Vector< Scalar, num_parametersparams () const
 
SOPHUS_FUNC Matrix< Scalar, 2, 2 > rotationMatrix () const
 
SOPHUS_FUNC void setComplex (Sophus::Vector2< Scalar > const &complex)
 
SOPHUS_FUNC void setRotationMatrix (Matrix< Scalar, 2, 2 > const &R)
 
SOPHUS_FUNC SO2Typeso2 ()
 
SOPHUS_FUNC SO2Type const & so2 () const
 
SOPHUS_FUNC TranslationTypetranslation ()
 
SOPHUS_FUNC TranslationType const & translation () const
 
SOPHUS_FUNC Eigen::internal::traits< Derived >::SO2Type::ComplexT const & unit_complex () const
 

Static Public Attributes

static constexpr int DoF = 3
 
static constexpr int N = 3
 Group transformations are 3x3 matrices. More...
 
static constexpr int num_parameters = 4
 

Detailed Description

template<class Derived>
class Sophus::SE2Base< Derived >

SE2 base type - implements SE2 class but is storage agnostic.

SE(2) is the group of rotations and translation in 2d. It is the semi-direct product of SO(2) and the 2d Euclidean vector space. The class is represented using a composition of SO2Group for rotation and a 2-vector for translation.

SE(2) is neither compact, nor a commutative group.

See SO2Group for more details of the rotation representation in 2d.

Definition at line 58 of file se2.hpp.

Member Typedef Documentation

◆ Adjoint

template<class Derived >
using Sophus::SE2Base< Derived >::Adjoint = Matrix<Scalar, DoF, DoF>

Definition at line 78 of file se2.hpp.

◆ HomogeneousPoint

template<class Derived >
using Sophus::SE2Base< Derived >::HomogeneousPoint = Vector3<Scalar>

Definition at line 75 of file se2.hpp.

◆ HomogeneousPointProduct

template<class Derived >
template<typename HPointDerived >
using Sophus::SE2Base< Derived >::HomogeneousPointProduct = Vector3<ReturnScalar<HPointDerived> >

Definition at line 95 of file se2.hpp.

◆ Line

template<class Derived >
using Sophus::SE2Base< Derived >::Line = ParametrizedLine2<Scalar>

Definition at line 76 of file se2.hpp.

◆ Point

template<class Derived >
using Sophus::SE2Base< Derived >::Point = Vector2<Scalar>

Definition at line 74 of file se2.hpp.

◆ PointProduct

template<class Derived >
template<typename PointDerived >
using Sophus::SE2Base< Derived >::PointProduct = Vector2<ReturnScalar<PointDerived> >

Definition at line 92 of file se2.hpp.

◆ ReturnScalar

template<class Derived >
template<typename OtherDerived >
using Sophus::SE2Base< Derived >::ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar>::ReturnType

For binary operations the return type is determined with the ScalarBinaryOpTraits feature of Eigen. This allows mixing concrete and Map types, as well as other compatible scalar types such as Ceres::Jet and double scalars with SE2 operations.

Definition at line 86 of file se2.hpp.

◆ Scalar

template<class Derived >
using Sophus::SE2Base< Derived >::Scalar = typename Eigen::internal::traits<Derived>::Scalar

Definition at line 60 of file se2.hpp.

◆ SE2Product

template<class Derived >
template<typename OtherDerived >
using Sophus::SE2Base< Derived >::SE2Product = SE2<ReturnScalar<OtherDerived> >

Definition at line 89 of file se2.hpp.

◆ SO2Type

template<class Derived >
using Sophus::SE2Base< Derived >::SO2Type = typename Eigen::internal::traits<Derived>::SO2Type

Definition at line 63 of file se2.hpp.

◆ Tangent

template<class Derived >
using Sophus::SE2Base< Derived >::Tangent = Vector<Scalar, DoF>

Definition at line 77 of file se2.hpp.

◆ Transformation

template<class Derived >
using Sophus::SE2Base< Derived >::Transformation = Matrix<Scalar, N, N>

Definition at line 73 of file se2.hpp.

◆ TranslationType

template<class Derived >
using Sophus::SE2Base< Derived >::TranslationType = typename Eigen::internal::traits<Derived>::TranslationType

Definition at line 62 of file se2.hpp.

Member Function Documentation

◆ Adj()

template<class Derived >
SOPHUS_FUNC Adjoint Sophus::SE2Base< Derived >::Adj ( ) const
inline

Adjoint transformation

This function return the adjoint transformation Ad of the group element A such that for all x it holds that hat(Ad_A * x) = A * hat(x) A^{-1}. See hat-operator below.

Definition at line 103 of file se2.hpp.

◆ cast()

template<class Derived >
template<class NewScalarType >
SOPHUS_FUNC SE2<NewScalarType> Sophus::SE2Base< Derived >::cast ( ) const
inline

Returns copy of instance casted to NewScalarType.

Definition at line 116 of file se2.hpp.

◆ Dx_this_mul_exp_x_at_0()

template<class Derived >
SOPHUS_FUNC Matrix<Scalar, num_parameters, DoF> Sophus::SE2Base< Derived >::Dx_this_mul_exp_x_at_0 ( ) const
inline

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

Definition at line 123 of file se2.hpp.

◆ inverse()

template<class Derived >
SOPHUS_FUNC SE2<Scalar> Sophus::SE2Base< Derived >::inverse ( ) const
inline

Returns group inverse.

Definition at line 145 of file se2.hpp.

◆ log()

template<class Derived >
SOPHUS_FUNC Tangent Sophus::SE2Base< Derived >::log ( ) const
inline

Logarithmic map

Computes the logarithm, the inverse of the group exponential which maps element of the group (rigid body transformations) to elements of the tangent space (twist).

To be specific, this function computes vee(logmat(.)) with logmat(.) being the matrix logarithm and vee(.) the vee-operator of SE(2).

Definition at line 160 of file se2.hpp.

◆ matrix()

template<class Derived >
SOPHUS_FUNC Transformation Sophus::SE2Base< Derived >::matrix ( ) const
inline

Returns 3x3 matrix representation of the instance.

It has the following form:

| R t | | o 1 |

where R is a 2x2 rotation matrix, t a translation 2-vector and o a 2-column vector of zeros.

Definition at line 200 of file se2.hpp.

◆ matrix2x3()

template<class Derived >
SOPHUS_FUNC Matrix<Scalar, 2, 3> Sophus::SE2Base< Derived >::matrix2x3 ( ) const
inline

Returns the significant first two rows of the matrix above.

Definition at line 210 of file se2.hpp.

◆ normalize()

template<class Derived >
SOPHUS_FUNC void Sophus::SE2Base< Derived >::normalize ( )
inline

Normalize SO2 element

It re-normalizes the SO2 element.

Definition at line 188 of file se2.hpp.

◆ operator*() [1/4]

template<class Derived >
template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 3>::value>::type>
SOPHUS_FUNC HomogeneousPointProduct<HPointDerived> Sophus::SE2Base< Derived >::operator* ( Eigen::MatrixBase< HPointDerived > const &  p) const
inline

Group action on homogeneous 2-points. See above for more details.

Definition at line 260 of file se2.hpp.

◆ operator*() [2/4]

template<class Derived >
template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 2>::value>::type>
SOPHUS_FUNC PointProduct<PointDerived> Sophus::SE2Base< Derived >::operator* ( Eigen::MatrixBase< PointDerived > const &  p) const
inline

Group action on 2-points.

This function rotates and translates a two dimensional point p by the SE(2) element bar_T_foo = (bar_R_foo, t_bar) (= rigid body transformation):

p_bar = bar_R_foo * p_foo + t_bar.

Definition at line 250 of file se2.hpp.

◆ operator*() [3/4]

template<class Derived >
SOPHUS_FUNC Line Sophus::SE2Base< Derived >::operator* ( Line const &  l) const
inline

Group action on lines.

This function rotates and translates a parametrized line l(t) = o + t * d by the SE(2) element:

Origin o is rotated and translated using SE(2) action Direction d is rotated using SO(2) action

Definition at line 275 of file se2.hpp.

◆ operator*() [4/4]

template<class Derived >
template<typename OtherDerived >
SOPHUS_FUNC SE2Product<OtherDerived> Sophus::SE2Base< Derived >::operator* ( SE2Base< OtherDerived > const &  other) const
inline

Group multiplication, which is rotation concatenation.

Definition at line 233 of file se2.hpp.

◆ operator*=()

template<class Derived >
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC SE2Base<Derived>& Sophus::SE2Base< Derived >::operator*= ( SE2Base< OtherDerived > const &  other)
inline

In-place group multiplication. This method is only valid if the return type of the multiplication is compatible with this SO2's Scalar type.

Definition at line 285 of file se2.hpp.

◆ operator=() [1/2]

template<class Derived >
SOPHUS_FUNC SE2Base& Sophus::SE2Base< Derived >::operator= ( SE2Base< Derived > const &  other)
default

Assignment operator.

◆ operator=() [2/2]

template<class Derived >
template<class OtherDerived >
SOPHUS_FUNC SE2Base<Derived>& Sophus::SE2Base< Derived >::operator= ( SE2Base< OtherDerived > const &  other)
inline

Assignment-like operator from OtherDerived.

Definition at line 224 of file se2.hpp.

◆ params()

template<class Derived >
SOPHUS_FUNC Sophus::Vector<Scalar, num_parameters> Sophus::SE2Base< Derived >::params ( ) const
inline

Returns internal parameters of SE(2).

It returns (c[0], c[1], t[0], t[1]), with c being the unit complex number, t the translation 3-vector.

Definition at line 295 of file se2.hpp.

◆ rotationMatrix()

template<class Derived >
SOPHUS_FUNC Matrix<Scalar, 2, 2> Sophus::SE2Base< Derived >::rotationMatrix ( ) const
inline

Returns rotation matrix.

Definition at line 303 of file se2.hpp.

◆ setComplex()

template<class Derived >
SOPHUS_FUNC void Sophus::SE2Base< Derived >::setComplex ( Sophus::Vector2< Scalar > const &  complex)
inline

Takes in complex number, and normalizes it.

Precondition: The complex number must not be close to zero.

Definition at line 311 of file se2.hpp.

◆ setRotationMatrix()

template<class Derived >
SOPHUS_FUNC void Sophus::SE2Base< Derived >::setRotationMatrix ( Matrix< Scalar, 2, 2 > const &  R)
inline

Sets so3 using rotation_matrix.

Precondition: R must be orthogonal and det(R)=1.

Definition at line 319 of file se2.hpp.

◆ so2() [1/2]

template<class Derived >
SOPHUS_FUNC SO2Type& Sophus::SE2Base< Derived >::so2 ( )
inline

Mutator of SO3 group.

Definition at line 331 of file se2.hpp.

◆ so2() [2/2]

template<class Derived >
SOPHUS_FUNC SO2Type const& Sophus::SE2Base< Derived >::so2 ( ) const
inline

Accessor of SO3 group.

Definition at line 336 of file se2.hpp.

◆ translation() [1/2]

template<class Derived >
SOPHUS_FUNC TranslationType& Sophus::SE2Base< Derived >::translation ( )
inline

Mutator of translation vector.

Definition at line 343 of file se2.hpp.

◆ translation() [2/2]

template<class Derived >
SOPHUS_FUNC TranslationType const& Sophus::SE2Base< Derived >::translation ( ) const
inline

Accessor of translation vector

Definition at line 350 of file se2.hpp.

◆ unit_complex()

template<class Derived >
SOPHUS_FUNC Eigen::internal::traits<Derived>::SO2Type::ComplexT const& Sophus::SE2Base< Derived >::unit_complex ( ) const
inline

Accessor of unit complex number.

Definition at line 358 of file se2.hpp.

Member Data Documentation

◆ DoF

template<class Derived >
constexpr int Sophus::SE2Base< Derived >::DoF = 3
staticconstexpr

Degrees of freedom of manifold, number of dimensions in tangent space (two for translation, three for rotation).

Definition at line 67 of file se2.hpp.

◆ N

template<class Derived >
constexpr int Sophus::SE2Base< Derived >::N = 3
staticconstexpr

Group transformations are 3x3 matrices.

Definition at line 72 of file se2.hpp.

◆ num_parameters

template<class Derived >
constexpr int Sophus::SE2Base< Derived >::num_parameters = 4
staticconstexpr

Number of internal parameters used (tuple for complex, two for translation).

Definition at line 70 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