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

#include <so3.hpp>

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

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

Public Member Functions

SOPHUS_FUNC Adjoint Adj () const
 Adjoint transformation. More...
 
template<class S = Scalar>
SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > angleX () const
 
template<class S = Scalar>
SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > angleY () const
 
template<class S = Scalar>
SOPHUS_FUNC enable_if_t< std::is_floating_point< S >::value, S > angleZ () const
 
template<class NewScalarType >
SOPHUS_FUNC SO3< NewScalarType > cast () const
 
SOPHUS_FUNC Scalardata ()
 
SOPHUS_FUNC Scalar const * data () const
 
SOPHUS_FUNC Matrix< Scalar, num_parameters, DoFDx_this_mul_exp_x_at_0 () const
 
SOPHUS_FUNC SO3< Scalarinverse () const
 
SOPHUS_FUNC Tangent log () const
 
SOPHUS_FUNC TangentAndTheta logAndTheta () const
 
SOPHUS_FUNC Transformation matrix () const
 
SOPHUS_FUNC void normalize ()
 
template<typename HPointDerived , typename = typename std::enable_if< IsFixedSizeVector<HPointDerived, 4>::value>::type>
SOPHUS_FUNC HomogeneousPointProduct< HPointDerived > operator* (Eigen::MatrixBase< HPointDerived > const &p) const
 Group action on homogeneous 3-points. See above for more details. More...
 
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 SO3Product< OtherDerived > operator* (SO3Base< OtherDerived > const &other) const
 
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC SO3Base< Derived > & operator*= (SO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC SO3Baseoperator= (SO3Base const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC SO3Base< Derived > & operator= (SO3Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sophus::Vector< Scalar, num_parametersparams () const
 
SOPHUS_FUNC void setQuaternion (Eigen::Quaternion< Scalar > const &quaternion)
 
SOPHUS_FUNC QuaternionType const & unit_quaternion () const
 

Static Public Attributes

static constexpr int DoF = 3
 Degrees of freedom of group, number of dimensions in tangent space. More...
 
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...
 

Private Member Functions

SOPHUS_FUNC QuaternionTypeunit_quaternion_nonconst ()
 

Detailed Description

template<class Derived>
class Sophus::SO3Base< Derived >

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

SO(3) is the group of rotations in 3d. As a matrix group, it is the set of matrices which are orthogonal such that R * R' = I (with R' being the transpose of R) and have a positive determinant. In particular, the determinant is 1. Internally, the group is represented as a unit quaternion. Unit quaternion can be seen as members of the special unitary group SU(2). SU(2) is a double cover of SO(3). Hence, for every rotation matrix R, there exist two unit quaternions: (r, v) and (-r, -v), with r the real part and v being the imaginary 3-vector part of the quaternion.

SO(3) is a compact, but non-commutative group. First it is compact since the set of rotation matrices is a closed and bounded set. Second it is non-commutative since the equation R_1 * R_2 = R_2 * R_1 does not hold in general. For example rotating an object by some degrees about its x-axis and then by some degrees about its y axis, does not lead to the same orientation when rotation first about y and then about x.

Class invariant: The 2-norm of unit_quaternion must be close to 1. Technically speaking, it must hold that:

|unit_quaternion().squaredNorm() - 1| <= Constants::epsilon().

Definition at line 74 of file so3.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 91 of file so3.hpp.

◆ HomogeneousPoint

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

Definition at line 88 of file so3.hpp.

◆ HomogeneousPointProduct

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

Definition at line 115 of file so3.hpp.

◆ Line

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

Definition at line 89 of file so3.hpp.

◆ Point

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

Definition at line 87 of file so3.hpp.

◆ PointProduct

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

Definition at line 112 of file so3.hpp.

◆ QuaternionType

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

Definition at line 78 of file so3.hpp.

◆ ReturnScalar

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

Definition at line 106 of file so3.hpp.

◆ Scalar

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

Definition at line 76 of file so3.hpp.

◆ SO3Product

template<class Derived >
template<typename OtherDerived >
using Sophus::SO3Base< Derived >::SO3Product = SO3<ReturnScalar<OtherDerived> >

Definition at line 109 of file so3.hpp.

◆ Tangent

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

Definition at line 90 of file so3.hpp.

◆ Transformation

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

Definition at line 86 of file so3.hpp.

Member Function Documentation

◆ Adj()

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

Definition at line 125 of file so3.hpp.

◆ angleX()

template<class Derived >
template<class S = Scalar>
SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, S> Sophus::SO3Base< Derived >::angleX ( ) const
inline

Extract rotation angle about canonical X-axis

Definition at line 130 of file so3.hpp.

◆ angleY()

template<class Derived >
template<class S = Scalar>
SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, S> Sophus::SO3Base< Derived >::angleY ( ) const
inline

Extract rotation angle about canonical Y-axis

Definition at line 139 of file so3.hpp.

◆ angleZ()

template<class Derived >
template<class S = Scalar>
SOPHUS_FUNC enable_if_t<std::is_floating_point<S>::value, S> Sophus::SO3Base< Derived >::angleZ ( ) const
inline

Extract rotation angle about canonical Z-axis

Definition at line 153 of file so3.hpp.

◆ cast()

template<class Derived >
template<class NewScalarType >
SOPHUS_FUNC SO3<NewScalarType> Sophus::SO3Base< Derived >::cast ( ) const
inline

Returns copy of instance casted to NewScalarType.

Definition at line 162 of file so3.hpp.

◆ data() [1/2]

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

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

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

Definition at line 174 of file so3.hpp.

◆ data() [2/2]

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

Const version of data() above.

Definition at line 180 of file so3.hpp.

◆ Dx_this_mul_exp_x_at_0()

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

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

Definition at line 186 of file so3.hpp.

◆ inverse()

template<class Derived >
SOPHUS_FUNC SO3<Scalar> Sophus::SO3Base< Derived >::inverse ( ) const
inline

Returns group inverse.

Definition at line 224 of file so3.hpp.

◆ log()

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

Logarithmic map

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

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

Definition at line 238 of file so3.hpp.

◆ logAndTheta()

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

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

Atan-based log thanks to

C. Hertzberg et al.: "Integrating Generic Sensor Fusion Algorithms with Sound State Representation through Encapsulation of Manifolds" Information Fusion, 2011

Definition at line 242 of file so3.hpp.

◆ matrix()

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

Returns 3x3 matrix representation of the instance.

For SO(3), the matrix representation is an orthogonal matrix R with det(R)=1, thus the so-called "rotation matrix".

Definition at line 305 of file so3.hpp.

◆ normalize()

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

It re-normalizes unit_quaternion to unit length.

Note: Because of the class invariant, there is typically no need to call this function directly.

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

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

Definition at line 372 of file so3.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::SO3Base< 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): p_bar = bar_R_foo * p_foo.

Since SO3 is internally represented by a unit quaternion q, it is implemented as p_bar = q * p_foo * q^{*} with q^{*} being the quaternion conjugate of q.

Geometrically, p is rotated by angle |omega| around the axis omega/|omega| with omega := vee(log(bar_R_foo)).

For vee-operator, see below.

NOTE: We cannot use Eigen's Quaternion transformVector because it always returns a Vector3 of the same Scalar as this quaternion, so it is not able to be applied to Jets and doubles correctly.

Definition at line 357 of file so3.hpp.

◆ operator*() [3/4]

template<class Derived >
SOPHUS_FUNC Line Sophus::SO3Base< 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:

Both direction d and origin o are rotated as a 3 dimensional point

Definition at line 385 of file so3.hpp.

◆ operator*() [4/4]

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

Group multiplication, which is rotation concatenation.

NOTE: We cannot use Eigen's Quaternion multiplication because it always returns a Quaternion of the same Scalar as this object, so it is not able to multiple Jets and doubles correctly.

Definition at line 324 of file so3.hpp.

◆ operator*=()

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

Definition at line 395 of file so3.hpp.

◆ operator=() [1/2]

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

Assignment operator.

◆ operator=() [2/2]

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

Assignment-like operator from OtherDerived.

Definition at line 316 of file so3.hpp.

◆ params()

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

Returns internal parameters of SO(3).

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

Definition at line 218 of file so3.hpp.

◆ setQuaternion()

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

Takes in quaternion, and normalizes it.

Precondition: The quaternion must not be close to zero.

Definition at line 404 of file so3.hpp.

◆ unit_quaternion()

template<class Derived >
SOPHUS_FUNC QuaternionType const& Sophus::SO3Base< Derived >::unit_quaternion ( ) const
inline

Accessor of unit quaternion.

Definition at line 411 of file so3.hpp.

◆ unit_quaternion_nonconst()

template<class Derived >
SOPHUS_FUNC QuaternionType& Sophus::SO3Base< Derived >::unit_quaternion_nonconst ( )
inlineprivate

Mutator of unit_quaternion is private to ensure class invariant. That is the quaternion must stay close to unit length.

Definition at line 419 of file so3.hpp.

Member Data Documentation

◆ DoF

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

Degrees of freedom of group, number of dimensions in tangent space.

Definition at line 81 of file so3.hpp.

◆ N

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

Group transformations are 3x3 matrices.

Definition at line 85 of file so3.hpp.

◆ num_parameters

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

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

Definition at line 83 of file so3.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