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

#include <rxso3.hpp>

Classes

struct  TangentAndTheta
 

Public Types

using Adjoint = Matrix< Scalar, DoF, DoF >
 
using HomogeneousPoint = Vector4< Scalar >
 
template<typename HPointDerived >
using HomogeneousPointProduct = Vector4< ReturnScalar< HPointDerived > >
 
using Line = ParametrizedLine3< Scalar >
 
using Point = Vector3< Scalar >
 
template<typename PointDerived >
using PointProduct = Vector3< ReturnScalar< PointDerived > >
 
using QuaternionType = typename Eigen::internal::traits< Derived >::QuaternionType
 
template<typename OtherDerived >
using ReturnScalar = typename Eigen::ScalarBinaryOpTraits< Scalar, typename OtherDerived::Scalar >::ReturnType
 
template<typename OtherDerived >
using RxSO3Product = RxSO3< 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
 
template<class NewScalarType >
SOPHUS_FUNC RxSO3< NewScalarType > cast () const
 
SOPHUS_FUNC Scalardata ()
 
SOPHUS_FUNC Scalar const * data () const
 
SOPHUS_FUNC RxSO3< Scalarinverse () const
 
SOPHUS_FUNC Tangent log () const
 
SOPHUS_FUNC TangentAndTheta logAndTheta () const
 
SOPHUS_FUNC Transformation matrix () const
 
template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 4>::value>::type>
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const
 
template<typename PointDerived , typename = typename std::enable_if< IsFixedSizeVector<PointDerived, 3>::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 RxSO3Product< OtherDerived > operator* (RxSO3Base< OtherDerived > const &other) const
 
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC RxSO3Base< Derived > & operator*= (RxSO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC RxSO3Baseoperator= (RxSO3Base const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC RxSO3Base< Derived > & operator= (RxSO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sophus::Vector< Scalar, num_parametersparams () const
 
SOPHUS_FUNC QuaternionType const & quaternion () const
 
SOPHUS_FUNC Transformation rotationMatrix () const
 
SOPHUS_FUNC Scalar scale () const
 
SOPHUS_FUNC void setQuaternion (Eigen::Quaternion< Scalar > const &quat)
 
SOPHUS_FUNC void setRotationMatrix (Transformation const &R)
 
SOPHUS_FUNC void setScale (Scalar const &scale)
 
SOPHUS_FUNC void setScaledRotationMatrix (Transformation const &sR)
 
SOPHUS_FUNC void setSO3 (SO3< Scalar > const &so3)
 
SOPHUS_FUNC SO3< Scalarso3 () 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
 Number of internal parameters used (quaternion is a 4-tuple). More...
 

Protected Member Functions

SOPHUS_FUNC QuaternionTypequaternion_nonconst ()
 

Detailed Description

template<class Derived>
class Sophus::RxSO3Base< Derived >

RxSO3 base type - implements RxSO3 class but is storage agnostic

This class implements the group R+ x SO(3), the direct product of the group of positive scalar 3x3 matrices (= isomorph to the positive real numbers) and the three-dimensional special orthogonal group SO(3). Geometrically, it is the group of rotation and scaling in three dimensions. As a matrix groups, RxSO3 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.

Internally, RxSO3 is represented by the group of non-zero quaternions. In particular, the scale equals the squared(!) norm of the quaternion q, s = |q|^2. This is a most compact representation since the degrees of freedom (DoF) of RxSO3 (=4) equals the number of internal parameters (=4).

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

quaternion().squaredNorm() >= 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 67 of file rxso3.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 85 of file rxso3.hpp.

◆ HomogeneousPoint

template<class Derived >
using Sophus::RxSO3Base< Derived >::HomogeneousPoint = Vector4<Scalar>

Definition at line 82 of file rxso3.hpp.

◆ HomogeneousPointProduct

template<class Derived >
template<typename HPointDerived >
using Sophus::RxSO3Base< Derived >::HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived> >

Definition at line 109 of file rxso3.hpp.

◆ Line

template<class Derived >
using Sophus::RxSO3Base< Derived >::Line = ParametrizedLine3<Scalar>

Definition at line 83 of file rxso3.hpp.

◆ Point

template<class Derived >
using Sophus::RxSO3Base< Derived >::Point = Vector3<Scalar>

Definition at line 81 of file rxso3.hpp.

◆ PointProduct

template<class Derived >
template<typename PointDerived >
using Sophus::RxSO3Base< Derived >::PointProduct = Vector3<ReturnScalar<PointDerived> >

Definition at line 106 of file rxso3.hpp.

◆ QuaternionType

template<class Derived >
using Sophus::RxSO3Base< Derived >::QuaternionType = typename Eigen::internal::traits<Derived>::QuaternionType

Definition at line 71 of file rxso3.hpp.

◆ ReturnScalar

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

Definition at line 100 of file rxso3.hpp.

◆ RxSO3Product

template<class Derived >
template<typename OtherDerived >
using Sophus::RxSO3Base< Derived >::RxSO3Product = RxSO3<ReturnScalar<OtherDerived> >

Definition at line 103 of file rxso3.hpp.

◆ Scalar

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

Definition at line 69 of file rxso3.hpp.

◆ Tangent

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

Definition at line 84 of file rxso3.hpp.

◆ Transformation

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

Definition at line 80 of file rxso3.hpp.

Member Function Documentation

◆ Adj()

template<class Derived >
SOPHUS_FUNC Adjoint Sophus::RxSO3Base< 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(3), it simply returns the rotation matrix corresponding to A.

Definition at line 119 of file rxso3.hpp.

◆ cast()

template<class Derived >
template<class NewScalarType >
SOPHUS_FUNC RxSO3<NewScalarType> Sophus::RxSO3Base< Derived >::cast ( ) const
inline

Returns copy of instance casted to NewScalarType.

Definition at line 129 of file rxso3.hpp.

◆ data() [1/2]

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

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

Note: The first three Scalars represent the imaginary parts, while the forth Scalar represent the real part.

Definition at line 141 of file rxso3.hpp.

◆ data() [2/2]

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

Const version of data() above.

Definition at line 145 of file rxso3.hpp.

◆ inverse()

template<class Derived >
SOPHUS_FUNC RxSO3<Scalar> Sophus::RxSO3Base< Derived >::inverse ( ) const
inline

Returns group inverse.

Definition at line 151 of file rxso3.hpp.

◆ log()

template<class Derived >
SOPHUS_FUNC Tangent Sophus::RxSO3Base< 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 RxSO3.

Definition at line 165 of file rxso3.hpp.

◆ logAndTheta()

template<class Derived >
SOPHUS_FUNC TangentAndTheta Sophus::RxSO3Base< Derived >::logAndTheta ( ) const
inline

As above, but also returns theta = |omega|.

Definition at line 169 of file rxso3.hpp.

◆ matrix()

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

Returns 3x3 matrix representation of the instance.

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

Definition at line 186 of file rxso3.hpp.

◆ operator*() [1/4]

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

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

Definition at line 279 of file rxso3.hpp.

◆ operator*() [2/4]

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

Group action on 3-points.

This function rotates a 3 dimensional point p by the SO3 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 264 of file rxso3.hpp.

◆ operator*() [3/4]

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

Group action on lines.

This function rotates a parametrized line l(t) = o + t * d by the SO3 element ans scales it by the scale factor:

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

Definition at line 293 of file rxso3.hpp.

◆ operator*() [4/4]

template<class Derived >
template<typename OtherDerived >
SOPHUS_FUNC RxSO3Product<OtherDerived> Sophus::RxSO3Base< Derived >::operator* ( RxSO3Base< 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.

Saturation to ensure class invariant.

Definition at line 237 of file rxso3.hpp.

◆ operator*=()

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

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

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

Definition at line 307 of file rxso3.hpp.

◆ operator=() [1/2]

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

Assignment operator.

◆ operator=() [2/2]

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

Assignment-like operator from OtherDerived.

Definition at line 224 of file rxso3.hpp.

◆ params()

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

Returns internal parameters of RxSO(3).

It returns (q.imag[0], q.imag[1], q.imag[2], q.real), with q being the quaternion.

Definition at line 318 of file rxso3.hpp.

◆ quaternion()

template<class Derived >
SOPHUS_FUNC QuaternionType const& Sophus::RxSO3Base< Derived >::quaternion ( ) const
inline

Accessor of quaternion.

Definition at line 334 of file rxso3.hpp.

◆ quaternion_nonconst()

template<class Derived >
SOPHUS_FUNC QuaternionType& Sophus::RxSO3Base< Derived >::quaternion_nonconst ( )
inlineprotected

Mutator of quaternion is private to ensure class invariant.

Definition at line 404 of file rxso3.hpp.

◆ rotationMatrix()

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

Returns rotation matrix.

Definition at line 340 of file rxso3.hpp.

◆ scale()

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

Returns scale.

Definition at line 349 of file rxso3.hpp.

◆ setQuaternion()

template<class Derived >
SOPHUS_FUNC void Sophus::RxSO3Base< Derived >::setQuaternion ( Eigen::Quaternion< Scalar > const &  quat)
inline

Sets non-zero quaternion

Precondition: quat must not be close to zero.

Definition at line 325 of file rxso3.hpp.

◆ setRotationMatrix()

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

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

Definition at line 353 of file rxso3.hpp.

◆ setScale()

template<class Derived >
SOPHUS_FUNC void Sophus::RxSO3Base< 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 366 of file rxso3.hpp.

◆ setScaledRotationMatrix()

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

Setter of quaternion using scaled rotation matrix sR.

Precondition: The 3x3 matrix must be "scaled orthogonal" and have a positive determinant.

Definition at line 377 of file rxso3.hpp.

◆ setSO3()

template<class Derived >
SOPHUS_FUNC void Sophus::RxSO3Base< Derived >::setSO3 ( SO3< Scalar > const &  so3)
inline

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

Definition at line 392 of file rxso3.hpp.

◆ so3()

template<class Derived >
SOPHUS_FUNC SO3<Scalar> Sophus::RxSO3Base< Derived >::so3 ( ) const
inline

Definition at line 399 of file rxso3.hpp.

Member Data Documentation

◆ DoF

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

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

Definition at line 75 of file rxso3.hpp.

◆ N

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

Group transformations are 3x3 matrices.

Definition at line 79 of file rxso3.hpp.

◆ num_parameters

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

Number of internal parameters used (quaternion is a 4-tuple).

Definition at line 77 of file rxso3.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