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

#include <sim2.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 RxSO2Type = typename Eigen::internal::traits< Derived >::RxSO2Type
 
using Scalar = typename Eigen::internal::traits< Derived >::Scalar
 
template<typename OtherDerived >
using Sim2Product = Sim2< ReturnScalar< OtherDerived > >
 
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 Sim2< NewScalarType > cast () const
 
SOPHUS_FUNC Eigen::internal::traits< Derived >::RxSO2Type::ComplexType const & complex () const
 
SOPHUS_FUNC Sim2< Scalarinverse () const
 
SOPHUS_FUNC Tangent log () const
 
SOPHUS_FUNC Transformation matrix () const
 
SOPHUS_FUNC Matrix< Scalar, 2, 3 > matrix2x3 () const
 
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 Sim2Product< OtherDerived > operator* (Sim2Base< OtherDerived > const &other) const
 
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC Sim2Base< Derived > & operator*= (Sim2Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sim2Baseoperator= (Sim2Base const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC Sim2Base< Derived > & operator= (Sim2Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sophus::Vector< Scalar, num_parametersparams () const
 
SOPHUS_FUNC Matrix2< ScalarrotationMatrix () const
 
SOPHUS_FUNC RxSO2Typerxso2 ()
 
SOPHUS_FUNC RxSO2Type const & rxso2 () const
 
SOPHUS_FUNC Scalar scale () const
 
SOPHUS_FUNC void setComplex (Vector2< Scalar > const &z)
 
SOPHUS_FUNC void setRotationMatrix (Matrix2< Scalar > &R)
 
SOPHUS_FUNC void setScale (Scalar const &scale)
 
SOPHUS_FUNC void setScaledRotationMatrix (Matrix2< Scalar > const &sR)
 
SOPHUS_FUNC TranslationTypetranslation ()
 
SOPHUS_FUNC TranslationType const & translation () const
 

Static Public Attributes

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

Detailed Description

template<class Derived>
class Sophus::Sim2Base< Derived >

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

Sim(2) is the group of rotations and translation and scaling in 2d. It is the semi-direct product of R+xSO(2) and the 2d Euclidean vector space. The class is represented using a composition of RxSO2 for scaling plus rotation and a 2-vector for translation.

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

See RxSO2 for more details of the scaling + rotation representation in 2d.

Definition at line 59 of file sim2.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 79 of file sim2.hpp.

◆ HomogeneousPoint

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

Definition at line 76 of file sim2.hpp.

◆ HomogeneousPointProduct

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

Definition at line 96 of file sim2.hpp.

◆ Line

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

Definition at line 77 of file sim2.hpp.

◆ Point

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

Definition at line 75 of file sim2.hpp.

◆ PointProduct

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

Definition at line 93 of file sim2.hpp.

◆ ReturnScalar

template<class Derived >
template<typename OtherDerived >
using Sophus::Sim2Base< 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 SIM2 operations.

Definition at line 87 of file sim2.hpp.

◆ RxSO2Type

template<class Derived >
using Sophus::Sim2Base< Derived >::RxSO2Type = typename Eigen::internal::traits<Derived>::RxSO2Type

Definition at line 64 of file sim2.hpp.

◆ Scalar

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

Definition at line 61 of file sim2.hpp.

◆ Sim2Product

template<class Derived >
template<typename OtherDerived >
using Sophus::Sim2Base< Derived >::Sim2Product = Sim2<ReturnScalar<OtherDerived> >

Definition at line 90 of file sim2.hpp.

◆ Tangent

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

Definition at line 78 of file sim2.hpp.

◆ Transformation

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

Definition at line 74 of file sim2.hpp.

◆ TranslationType

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

Definition at line 63 of file sim2.hpp.

Member Function Documentation

◆ Adj()

template<class Derived >
SOPHUS_FUNC Adjoint Sophus::Sim2Base< 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 104 of file sim2.hpp.

◆ cast()

template<class Derived >
template<class NewScalarType >
SOPHUS_FUNC Sim2<NewScalarType> Sophus::Sim2Base< Derived >::cast ( ) const
inline

Returns copy of instance casted to NewScalarType.

Definition at line 121 of file sim2.hpp.

◆ complex()

template<class Derived >
SOPHUS_FUNC Eigen::internal::traits<Derived>::RxSO2Type::ComplexType const& Sophus::Sim2Base< Derived >::complex ( ) const
inline

Accessor of complex number.

Definition at line 293 of file sim2.hpp.

◆ inverse()

template<class Derived >
SOPHUS_FUNC Sim2<Scalar> Sophus::Sim2Base< Derived >::inverse ( ) const
inline

Returns group inverse.

Definition at line 128 of file sim2.hpp.

◆ log()

template<class Derived >
SOPHUS_FUNC Tangent Sophus::Sim2Base< 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 Sim(2).

The derivation of the closed-form Sim(2) logarithm for is done analogously to the closed-form solution of the SE(2) logarithm, see J. Gallier, D. Xu, "Computing exponentials of skew symmetric matrices and logarithms of orthogonal matrices", IJRA 2002. https:///pdfs.semanticscholar.org/cfe3/e4b39de63c8cabd89bf3feff7f5449fc981d.pdf (Sec. 6., pp. 8)

Definition at line 143 of file sim2.hpp.

◆ matrix()

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

Returns 3x3 matrix representation of the instance.

It has the following form:

| s*R t | | o 1 |

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

Definition at line 174 of file sim2.hpp.

◆ matrix2x3()

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

Returns the significant first two rows of the matrix above.

Definition at line 184 of file sim2.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::Sim2Base< Derived >::operator* ( Eigen::MatrixBase< HPointDerived > const &  p) const
inline

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

Definition at line 238 of file sim2.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::Sim2Base< Derived >::operator* ( Eigen::MatrixBase< PointDerived > const &  p) const
inline

Group action on 2-points.

This function rotates, scales and translates a two dimensional point p by the Sim(2) element (bar_sR_foo, t_bar) (= similarity transformation):

p_bar = bar_sR_foo * p_foo + t_bar.

Definition at line 228 of file sim2.hpp.

◆ operator*() [3/4]

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

Group action on lines.

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

Origin o is rotated, scaled and translated Direction d is rotated

Definition at line 253 of file sim2.hpp.

◆ operator*() [4/4]

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

Group multiplication, which is rotation plus scaling concatenation.

Note: That scaling is calculated with saturation. See RxSO2 for details.

Definition at line 211 of file sim2.hpp.

◆ operator*=()

template<class Derived >
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC Sim2Base<Derived>& Sophus::Sim2Base< Derived >::operator*= ( Sim2Base< 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 275 of file sim2.hpp.

◆ operator=() [1/2]

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

Assignment operator.

◆ operator=() [2/2]

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

Assignment-like operator from OtherDerived.

Definition at line 198 of file sim2.hpp.

◆ params()

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

Returns internal parameters of Sim(2).

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

Definition at line 263 of file sim2.hpp.

◆ rotationMatrix()

template<class Derived >
SOPHUS_FUNC Matrix2<Scalar> Sophus::Sim2Base< Derived >::rotationMatrix ( ) const
inline

Returns Rotation matrix

Definition at line 299 of file sim2.hpp.

◆ rxso2() [1/2]

template<class Derived >
SOPHUS_FUNC RxSO2Type& Sophus::Sim2Base< Derived >::rxso2 ( )
inline

Mutator of SO2 group.

Definition at line 305 of file sim2.hpp.

◆ rxso2() [2/2]

template<class Derived >
SOPHUS_FUNC RxSO2Type const& Sophus::Sim2Base< Derived >::rxso2 ( ) const
inline

Accessor of SO2 group.

Definition at line 311 of file sim2.hpp.

◆ scale()

template<class Derived >
SOPHUS_FUNC Scalar Sophus::Sim2Base< Derived >::scale ( ) const
inline

Returns scale.

Definition at line 317 of file sim2.hpp.

◆ setComplex()

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

Setter of non-zero complex number.

Precondition: z must not be close to zero.

Definition at line 285 of file sim2.hpp.

◆ setRotationMatrix()

template<class Derived >
SOPHUS_FUNC void Sophus::Sim2Base< Derived >::setRotationMatrix ( Matrix2< Scalar > &  R)
inline

Setter of complex number using rotation matrix R, leaves scale as is.

Definition at line 321 of file sim2.hpp.

◆ setScale()

template<class Derived >
SOPHUS_FUNC void Sophus::Sim2Base< Derived >::setScale ( Scalar const &  scale)
inline

Sets scale and leaves rotation as is.

Note: This function as a significant computational cost, since it has to call the square root twice.

Definition at line 330 of file sim2.hpp.

◆ setScaledRotationMatrix()

template<class Derived >
SOPHUS_FUNC void Sophus::Sim2Base< Derived >::setScaledRotationMatrix ( Matrix2< Scalar > const &  sR)
inline

Setter of complexnumber using scaled rotation matrix sR.

Precondition: The 2x2 matrix must be "scaled orthogonal" and have a positive determinant.

Definition at line 337 of file sim2.hpp.

◆ translation() [1/2]

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

Mutator of translation vector

Definition at line 343 of file sim2.hpp.

◆ translation() [2/2]

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

Accessor of translation vector

Definition at line 349 of file sim2.hpp.

Member Data Documentation

◆ DoF

template<class Derived >
constexpr int Sophus::Sim2Base< Derived >::DoF = 4
staticconstexpr

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

Definition at line 68 of file sim2.hpp.

◆ N

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

Group transformations are 3x3 matrices.

Definition at line 73 of file sim2.hpp.

◆ num_parameters

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

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

Definition at line 71 of file sim2.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