Template Class SE3Base

Class Documentation

template<class Derived>
class SE3Base

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

SE(3) is the group of rotations and translation in 3d. It is the semi-direct product of SO(3) and the 3d Euclidean vector space. The class is represented using a composition of SO3 for rotation and a one 3-vector for translation.

SE(3) is neither compact, nor a commutative group.

See SO3 for more details of the rotation representation in 3d.

Public Types

using Scalar = typename Eigen::internal::traits<Derived>::Scalar
using TranslationType = typename Eigen::internal::traits<Derived>::TranslationType
using SO3Type = typename Eigen::internal::traits<Derived>::SO3Type
using QuaternionType = typename SO3Type::QuaternionType
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 SE3 operations.

template<typename OtherDerived>
using SE3Product = SE3<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.

inline Scalar angleX() const

Extract rotation angle about canonical X-axis

inline Scalar angleY() const

Extract rotation angle about canonical Y-axis

inline Scalar angleZ() const

Extract rotation angle about canonical Z-axis

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

Returns copy of instance casted to NewScalarType.

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

Returns derivative of this * 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 SE3< 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 (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 SE(3).

inline SOPHUS_FUNC void normalize ()

It re-normalizes the SO3 element.

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

inline SOPHUS_FUNC Transformation matrix () const

Returns 4x4 matrix representation of the instance.

It has the following form:

| R t | | o 1 |

where R is a 3x3 rotation matrix, t a translation 3-vector and o a 3-column vector of zeros.

inline SOPHUS_FUNC Matrix< Scalar, 3, 4 > matrix3x4 () const

Returns the significant first three rows of the matrix above.

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

Assignment-like operator from OtherDerived.

template<typename OtherDerived> inline SOPHUS_FUNC SE3Product< OtherDerived > operator* (SE3Base< 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 and translates a three dimensional point p by the SE(3) element bar_T_foo = (bar_R_foo, t_bar) (= rigid body transformation):

p_bar = bar_R_foo * p_foo + t_bar.

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 and translates a parametrized line l(t) = o + t * d by the SE(3) element:

Origin is transformed using SE(3) action Direction is transformed using rotation part

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

Group action on planes.

This function rotates and translates a plane n.x + d = 0 by the SE(3) element:

Normal vector n is rotated Offset d is adjusted for translation

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

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

inline SOPHUS_FUNC Matrix3< Scalar > rotationMatrix () const

Returns rotation matrix.

inline SOPHUS_FUNC SO3Type & so3 ()

Mutator of SO3 group.

inline SOPHUS_FUNC SO3Type const  & so3 () const

Accessor of SO3 group.

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

Takes in quaternion, and normalizes it.

Precondition: The quaternion must not be close to zero.

inline SOPHUS_FUNC void setRotationMatrix (Matrix3< Scalar > const &R)

Sets so3 using rotation_matrix.

Precondition: R must be orthogonal and det(R)=1.

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

Returns internal parameters of SE(3).

It returns (q.imag[0], q.imag[1], q.imag[2], q.real, t[0], t[1], t[2]), with q being the unit quaternion, t the translation 3-vector.

inline SOPHUS_FUNC TranslationType & translation ()

Mutator of translation vector.

inline SOPHUS_FUNC TranslationType const  & translation () const

Accessor of translation vector

inline SOPHUS_FUNC QuaternionType const  & unit_quaternion () const

Accessor of unit quaternion.

Public Static Attributes

static constexpr int DoF = 6

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

static constexpr int num_parameters = 7

Number of internal parameters used (4-tuple for quaternion, three for translation).

static constexpr int N = 4

Group transformations are 4x4 matrices.

static constexpr int Dim = 3

Points are 3-dimensional.