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

#include <rxso2.hpp>

Inheritance diagram for Sophus::RxSO2Base< Derived >:
Inheritance graph
[legend]

Public Types

using Adjoint = Matrix< Scalar, DoF, DoF >
 
using ComplexType = typename Eigen::internal::traits< Derived >::ComplexType
 
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
 
template<typename OtherDerived >
using RxSO2Product = RxSO2< ReturnScalar< OtherDerived > >
 
using Scalar = typename Eigen::internal::traits< Derived >::Scalar
 
using Tangent = Vector< Scalar, DoF >
 
using Transformation = Matrix< Scalar, N, N >
 

Public Member Functions

SOPHUS_FUNC Adjoint Adj () const
 
SOPHUS_FUNC Scalar angle () const
 
template<class NewScalarType >
SOPHUS_FUNC RxSO2< NewScalarType > cast () const
 
SOPHUS_FUNC ComplexType const & complex () const
 
SOPHUS_FUNC Scalardata ()
 
SOPHUS_FUNC Scalar const * data () const
 
SOPHUS_FUNC RxSO2< Scalarinverse () const
 
SOPHUS_FUNC Tangent log () const
 
SOPHUS_FUNC Transformation matrix () 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 RxSO2Product< OtherDerived > operator* (RxSO2Base< OtherDerived > const &other) const
 
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC RxSO2Base< Derived > & operator*= (RxSO2Base< OtherDerived > const &other)
 
SOPHUS_FUNC RxSO2Baseoperator= (RxSO2Base const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC RxSO2Base< Derived > & operator= (RxSO2Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sophus::Vector< Scalar, num_parametersparams () const
 
SOPHUS_FUNC Transformation rotationMatrix () const
 
SOPHUS_FUNC Scalar scale () const
 
SOPHUS_FUNC void setAngle (Scalar const &theta)
 
SOPHUS_FUNC void setComplex (Vector2< Scalar > const &z)
 
SOPHUS_FUNC void setRotationMatrix (Transformation const &R)
 
SOPHUS_FUNC void setScale (Scalar const &scale)
 
SOPHUS_FUNC void setScaledRotationMatrix (Transformation const &sR)
 
SOPHUS_FUNC void setSO2 (SO2< Scalar > const &so2)
 
SOPHUS_FUNC SO2< Scalarso2 () const
 

Static Public Attributes

static constexpr int DoF = 2
 
static constexpr int N = 2
 Group transformations are 2x2 matrices. More...
 
static constexpr int num_parameters = 2
 Number of internal parameters used (complex number is a tuple). More...
 

Protected Member Functions

SOPHUS_FUNC ComplexTypecomplex_nonconst ()
 

Detailed Description

template<class Derived>
class Sophus::RxSO2Base< Derived >

RxSO2 base type - implements RxSO2 class but is storage agnostic

This class implements the group R+ x SO(2), the direct product of the group of positive scalar 2x2 matrices (= isomorph to the positive real numbers) and the two-dimensional special orthogonal group SO(2). Geometrically, it is the group of rotation and scaling in two dimensions. As a matrix groups, R+ x SO(2) consists of matrices of the form s * R where R is an orthogonal matrix with det(R) = 1 and s > 0 being a positive real number. In particular, it has the following form:

| s * cos(theta)  s * -sin(theta) |
| s * sin(theta)  s *  cos(theta) |

where theta being the rotation angle. Internally, it is represented by the first column of the rotation matrix, or in other words by a non-zero complex number.

R+ x SO(2) is not compact, but a commutative group. First it is not compact since the scale factor is not bound. Second it is commutative since sR(alpha, s1) * sR(beta, s2) = sR(beta, s2) * sR(alpha, s1), simply because alpha + beta = beta + alpha and s1 * s2 = s2 * s1 with alpha and beta being rotation angles and s1, s2 being scale factors.

This class has the explicit class invariant that the scale s is not too close to zero. Strictly speaking, it must hold that:

complex().norm() >= Constants::epsilon().

In order to obey this condition, group multiplication is implemented with saturation such that a product always has a scale which is equal or greater this threshold.

Definition at line 76 of file rxso2.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 93 of file rxso2.hpp.

◆ ComplexType

template<class Derived >
using Sophus::RxSO2Base< Derived >::ComplexType = typename Eigen::internal::traits<Derived>::ComplexType

Definition at line 79 of file rxso2.hpp.

◆ HomogeneousPoint

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

Definition at line 90 of file rxso2.hpp.

◆ HomogeneousPointProduct

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

Definition at line 110 of file rxso2.hpp.

◆ Line

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

Definition at line 91 of file rxso2.hpp.

◆ Point

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

Definition at line 89 of file rxso2.hpp.

◆ PointProduct

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

Definition at line 107 of file rxso2.hpp.

◆ ReturnScalar

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

Definition at line 101 of file rxso2.hpp.

◆ RxSO2Product

template<class Derived >
template<typename OtherDerived >
using Sophus::RxSO2Base< Derived >::RxSO2Product = RxSO2<ReturnScalar<OtherDerived> >

Definition at line 104 of file rxso2.hpp.

◆ Scalar

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

Definition at line 78 of file rxso2.hpp.

◆ Tangent

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

Definition at line 92 of file rxso2.hpp.

◆ Transformation

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

Definition at line 88 of file rxso2.hpp.

Member Function Documentation

◆ Adj()

template<class Derived >
SOPHUS_FUNC Adjoint Sophus::RxSO2Base< 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.

For RxSO(2), it simply returns the identity matrix.

Definition at line 120 of file rxso2.hpp.

◆ angle()

template<class Derived >
SOPHUS_FUNC Scalar Sophus::RxSO2Base< Derived >::angle ( ) const
inline

Returns rotation angle.

Definition at line 124 of file rxso2.hpp.

◆ cast()

template<class Derived >
template<class NewScalarType >
SOPHUS_FUNC RxSO2<NewScalarType> Sophus::RxSO2Base< Derived >::cast ( ) const
inline

Returns copy of instance casted to NewScalarType.

Definition at line 129 of file rxso2.hpp.

◆ complex()

template<class Derived >
SOPHUS_FUNC ComplexType const& Sophus::RxSO2Base< Derived >::complex ( ) const
inline

Accessor of complex.

Definition at line 305 of file rxso2.hpp.

◆ complex_nonconst()

template<class Derived >
SOPHUS_FUNC ComplexType& Sophus::RxSO2Base< Derived >::complex_nonconst ( )
inlineprotected

Mutator of complex is private to ensure class invariant.

Definition at line 367 of file rxso2.hpp.

◆ data() [1/2]

template<class Derived >
SOPHUS_FUNC Scalar* Sophus::RxSO2Base< Derived >::data ( )
inline

This provides unsafe read/write access to internal data. RxSO(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 is not set close to zero.

Note: The first parameter represents the real part, while the second parameter represent the imaginary part.

Definition at line 141 of file rxso2.hpp.

◆ data() [2/2]

template<class Derived >
SOPHUS_FUNC Scalar const* Sophus::RxSO2Base< Derived >::data ( ) const
inline

Const version of data() above.

Definition at line 145 of file rxso2.hpp.

◆ inverse()

template<class Derived >
SOPHUS_FUNC RxSO2<Scalar> Sophus::RxSO2Base< Derived >::inverse ( ) const
inline

Returns group inverse.

Definition at line 149 of file rxso2.hpp.

◆ log()

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

Logarithmic map

Computes the logarithm, the inverse of the group exponential which maps element of the group (scaled rotation matrices) to elements of the tangent space (rotation-vector plus logarithm of scale factor).

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

Definition at line 165 of file rxso2.hpp.

◆ matrix()

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

Returns 2x2 matrix representation of the instance.

For RxSO2, the matrix representation is an scaled orthogonal matrix sR with det(R)=s^2, thus a scaled rotation matrix R with scale s.

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

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

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

Group action on 2-points.

This function rotates a 2 dimensional point p by the SO2 element bar_R_foo (= rotation matrix) and scales it by the scale factor s:

p_bar = s * (bar_R_foo * p_foo).

Definition at line 242 of file rxso2.hpp.

◆ operator*() [3/4]

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

Group action on lines.

This function rotates a parameterized line l(t) = o + t * d by the SO2 element and scales it by the scale factor

Origin o is rotated and scaled Direction d is rotated (preserving it's norm)

Definition at line 266 of file rxso2.hpp.

◆ operator*() [4/4]

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

Group multiplication, which is rotation concatenation and scale multiplication.

Note: This function performs saturation for products close to zero in order to ensure the class invariant.

complex multiplication

Saturation to ensure class invariant.

Definition at line 208 of file rxso2.hpp.

◆ operator*=()

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

Note: This function performs saturation for products close to zero in order to ensure the class invariant.

Definition at line 279 of file rxso2.hpp.

◆ operator=() [1/2]

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

Assignment operator.

◆ operator=() [2/2]

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

Assignment-like operator from OtherDerived.

Definition at line 195 of file rxso2.hpp.

◆ params()

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

Returns internal parameters of RxSO(2).

It returns (c[0], c[1]), with c being the complex number.

Definition at line 289 of file rxso2.hpp.

◆ rotationMatrix()

template<class Derived >
SOPHUS_FUNC Transformation Sophus::RxSO2Base< Derived >::rotationMatrix ( ) const
inline

Returns rotation matrix.

Definition at line 311 of file rxso2.hpp.

◆ scale()

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

Returns scale.

Definition at line 320 of file rxso2.hpp.

◆ setAngle()

template<class Derived >
SOPHUS_FUNC void Sophus::RxSO2Base< Derived >::setAngle ( Scalar const &  theta)
inline

Setter of rotation angle, leaves scale as is.

Definition at line 324 of file rxso2.hpp.

◆ setComplex()

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

Sets non-zero complex

Precondition: z must not be close to zero.

Definition at line 296 of file rxso2.hpp.

◆ setRotationMatrix()

template<class Derived >
SOPHUS_FUNC void Sophus::RxSO2Base< Derived >::setRotationMatrix ( Transformation const &  R)
inline

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

Precondition: R must be orthogonal with determinant of one.

Definition at line 330 of file rxso2.hpp.

◆ setScale()

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

Sets scale and leaves rotation as is.

Definition at line 336 of file rxso2.hpp.

◆ setScaledRotationMatrix()

template<class Derived >
SOPHUS_FUNC void Sophus::RxSO2Base< Derived >::setScaledRotationMatrix ( Transformation const &  sR)
inline

Setter of complex number using scaled rotation matrix sR.

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

Definition at line 347 of file rxso2.hpp.

◆ setSO2()

template<class Derived >
SOPHUS_FUNC void Sophus::RxSO2Base< Derived >::setSO2 ( SO2< Scalar > const &  so2)
inline

Setter of SO(2) rotations, leaves scale as is.

Definition at line 355 of file rxso2.hpp.

◆ so2()

template<class Derived >
SOPHUS_FUNC SO2<Scalar> Sophus::RxSO2Base< Derived >::so2 ( ) const
inline

Definition at line 362 of file rxso2.hpp.

Member Data Documentation

◆ DoF

template<class Derived >
constexpr int Sophus::RxSO2Base< Derived >::DoF = 2
staticconstexpr

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

Definition at line 83 of file rxso2.hpp.

◆ N

template<class Derived >
constexpr int Sophus::RxSO2Base< Derived >::N = 2
staticconstexpr

Group transformations are 2x2 matrices.

Definition at line 87 of file rxso2.hpp.

◆ num_parameters

template<class Derived >
constexpr int Sophus::RxSO2Base< Derived >::num_parameters = 2
staticconstexpr

Number of internal parameters used (complex number is a tuple).

Definition at line 85 of file rxso2.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