Template Class SO3Base

Nested Relationships

Nested Types

Inheritance Relationships

Derived Type

Class Documentation

template<class Derived>
class SO3Base

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().

Subclassed by Sophus::SO3< Scalar, Options >

Public Types

using Scalar = typename Eigen::internal::traits<Derived>::Scalar
using QuaternionType = typename Eigen::internal::traits<Derived>::QuaternionType
using QuaternionTemporaryType = Eigen::Quaternion<Scalar, Options>
using Transformation = Matrix<Scalar, N, N>
using Point = Vector3<Scalar>
using HomogeneousPoint = Vector4<Scalar>
using Line = ParametrizedLine3<Scalar>
using Hyperplane = Hyperplane3<Scalar>
using Tangent = Vector<Scalar, DoF>
using Adjoint = Matrix<Scalar, DoF, DoF>
template<typename OtherDerived>
using 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.

template<typename OtherDerived>
using SO3Product = SO3<ReturnScalar<OtherDerived>>
template<typename PointDerived>
using PointProduct = Vector3<ReturnScalar<PointDerived>>
template<typename HPointDerived>
using HomogeneousPointProduct = Vector4<ReturnScalar<HPointDerived>>

Public Functions

inline SOPHUS_FUNC Adjoint Adj () const

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.

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

Extract rotation angle about canonical X-axis

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

Extract rotation angle about canonical Y-axis

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

Extract rotation angle about canonical Z-axis

template<class NewScalarType> inline SOPHUS_FUNC SO3< NewScalarType > cast () const

Returns copy of instance casted to NewScalarType.

inline SOPHUS_FUNC Scalar * data ()

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.

inline SOPHUS_FUNC Scalar const  * data () const

Const version of data() above.

inline SOPHUS_FUNC Matrix< Scalar, num_parameters, DoF > Dx_this_mul_exp_x_at_0 () const

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

inline SOPHUS_FUNC Matrix< Scalar, DoF, num_parameters > Dx_log_this_inv_by_x_at_this () const

Returns derivative of log(this^{-1} * x) by x at x=this.

inline SOPHUS_FUNC Sophus::Vector< Scalar, num_parameters > params () const

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.

inline SOPHUS_FUNC SO3< Scalar > inverse () const

Returns group inverse.

inline SOPHUS_FUNC Tangent log () const

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).

inline SOPHUS_FUNC TangentAndTheta logAndTheta () const

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

inline SOPHUS_FUNC void normalize ()

It re-normalizes unit_quaternion to unit length.

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

inline SOPHUS_FUNC Transformation matrix () const

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”.

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

Assignment-like operator from OtherDerived.

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

Group multiplication, which is rotation concatenation.

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

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.

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

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

inline SOPHUS_FUNC Line operator* (Line const &l) const

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

inline SOPHUS_FUNC Hyperplane operator* (Hyperplane const &p) const

Group action on planes.

This function rotates a plane n.x + d = 0 by the SO3 element:

Normal vector n is rotated Offset d is left unchanged

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

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

inline SOPHUS_FUNC void setQuaternion (Eigen::Quaternion< Scalar > const &quaternion)

Takes in quaternion, and normalizes it.

Precondition: The quaternion must not be close to zero.

inline SOPHUS_FUNC QuaternionType const  & unit_quaternion () const

Accessor of unit quaternion.

Public Static Functions

template<typename QuaternionProductType, typename QuaternionTypeA, typename QuaternionTypeB> static inline SOPHUS_FUNC QuaternionProductType QuaternionProduct (const QuaternionTypeA &a, const QuaternionTypeB &b)

Public Static Attributes

static constexpr int Options = Eigen::internal::traits<Derived>::Options
static constexpr int DoF = 3

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

static constexpr int num_parameters = 4

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

static constexpr int N = 3

Group transformations are 3x3 matrices.

static constexpr int Dim = 3

Points are 3-dimensional.

struct TangentAndTheta

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW Tangent tangent
Scalar theta