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

#include <se3.hpp>

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 SO3Type::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 SE3Product = SE3< ReturnScalar< OtherDerived > >
 
using SO3Type = typename Eigen::internal::traits< Derived >::SO3Type
 
using Tangent = Vector< Scalar, DoF >
 
using Transformation = Matrix< Scalar, N, N >
 
using TranslationType = typename Eigen::internal::traits< Derived >::TranslationType
 

Public Member Functions

SOPHUS_FUNC Adjoint Adj () const
 
Scalar angleX () const
 
Scalar angleY () const
 
Scalar angleZ () const
 
template<class NewScalarType >
SOPHUS_FUNC SE3< NewScalarType > cast () const
 
SOPHUS_FUNC Matrix< Scalar, num_parameters, DoFDx_this_mul_exp_x_at_0 () const
 
SOPHUS_FUNC SE3< Scalarinverse () const
 
SOPHUS_FUNC Tangent log () const
 
SOPHUS_FUNC Transformation matrix () const
 
SOPHUS_FUNC Matrix< Scalar, 3, 4 > matrix3x4 () 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
 
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 SE3Product< OtherDerived > operator* (SE3Base< OtherDerived > const &other) const
 
template<typename OtherDerived , typename = typename std::enable_if< std::is_same<Scalar, ReturnScalar<OtherDerived>>::value>::type>
SOPHUS_FUNC SE3Base< Derived > & operator*= (SE3Base< OtherDerived > const &other)
 
SOPHUS_FUNC SE3Baseoperator= (SE3Base const &other)=default
 
template<class OtherDerived >
SOPHUS_FUNC SE3Base< Derived > & operator= (SE3Base< OtherDerived > const &other)
 
SOPHUS_FUNC Sophus::Vector< Scalar, num_parametersparams () const
 
SOPHUS_FUNC Matrix3< ScalarrotationMatrix () const
 
SOPHUS_FUNC void setQuaternion (Eigen::Quaternion< Scalar > const &quat)
 
SOPHUS_FUNC void setRotationMatrix (Matrix3< Scalar > const &R)
 
SOPHUS_FUNC SO3Typeso3 ()
 
SOPHUS_FUNC SO3Type const & so3 () const
 
SOPHUS_FUNC TranslationTypetranslation ()
 
SOPHUS_FUNC TranslationType const & translation () const
 
SOPHUS_FUNC QuaternionType const & unit_quaternion () const
 

Static Public Attributes

static constexpr int DoF = 6
 
static constexpr int N = 4
 Group transformations are 4x4 matrices. More...
 
static constexpr int num_parameters = 7
 

Detailed Description

template<class Derived>
class Sophus::SE3Base< Derived >

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.

Definition at line 58 of file se3.hpp.

Member Typedef Documentation

◆ Adjoint

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

Definition at line 78 of file se3.hpp.

◆ HomogeneousPoint

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

Definition at line 75 of file se3.hpp.

◆ HomogeneousPointProduct

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

Definition at line 95 of file se3.hpp.

◆ Line

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

Definition at line 76 of file se3.hpp.

◆ Point

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

Definition at line 74 of file se3.hpp.

◆ PointProduct

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

Definition at line 92 of file se3.hpp.

◆ QuaternionType

template<class Derived >
using Sophus::SE3Base< Derived >::QuaternionType = typename SO3Type::QuaternionType

Definition at line 64 of file se3.hpp.

◆ ReturnScalar

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

Definition at line 86 of file se3.hpp.

◆ Scalar

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

Definition at line 60 of file se3.hpp.

◆ SE3Product

template<class Derived >
template<typename OtherDerived >
using Sophus::SE3Base< Derived >::SE3Product = SE3<ReturnScalar<OtherDerived> >

Definition at line 89 of file se3.hpp.

◆ SO3Type

template<class Derived >
using Sophus::SE3Base< Derived >::SO3Type = typename Eigen::internal::traits<Derived>::SO3Type

Definition at line 63 of file se3.hpp.

◆ Tangent

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

Definition at line 77 of file se3.hpp.

◆ Transformation

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

Definition at line 73 of file se3.hpp.

◆ TranslationType

template<class Derived >
using Sophus::SE3Base< Derived >::TranslationType = typename Eigen::internal::traits<Derived>::TranslationType

Definition at line 62 of file se3.hpp.

Member Function Documentation

◆ Adj()

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

Definition at line 103 of file se3.hpp.

◆ angleX()

template<class Derived >
Scalar Sophus::SE3Base< Derived >::angleX ( ) const
inline

Extract rotation angle about canonical X-axis

Definition at line 115 of file se3.hpp.

◆ angleY()

template<class Derived >
Scalar Sophus::SE3Base< Derived >::angleY ( ) const
inline

Extract rotation angle about canonical Y-axis

Definition at line 119 of file se3.hpp.

◆ angleZ()

template<class Derived >
Scalar Sophus::SE3Base< Derived >::angleZ ( ) const
inline

Extract rotation angle about canonical Z-axis

Definition at line 123 of file se3.hpp.

◆ cast()

template<class Derived >
template<class NewScalarType >
SOPHUS_FUNC SE3<NewScalarType> Sophus::SE3Base< Derived >::cast ( ) const
inline

Returns copy of instance casted to NewScalarType.

Definition at line 128 of file se3.hpp.

◆ Dx_this_mul_exp_x_at_0()

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

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

Definition at line 135 of file se3.hpp.

◆ inverse()

template<class Derived >
SOPHUS_FUNC SE3<Scalar> Sophus::SE3Base< Derived >::inverse ( ) const
inline

Returns group inverse.

Definition at line 208 of file se3.hpp.

◆ log()

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

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

Definition at line 223 of file se3.hpp.

◆ matrix()

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

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.

Definition at line 275 of file se3.hpp.

◆ matrix3x4()

template<class Derived >
SOPHUS_FUNC Matrix<Scalar, 3, 4> Sophus::SE3Base< Derived >::matrix3x4 ( ) const
inline

Returns the significant first three rows of the matrix above.

Definition at line 285 of file se3.hpp.

◆ normalize()

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

It re-normalizes the SO3 element.

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

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

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

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

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.

Definition at line 325 of file se3.hpp.

◆ operator*() [3/4]

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

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

Definition at line 350 of file se3.hpp.

◆ operator*() [4/4]

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

Group multiplication, which is rotation concatenation.

Definition at line 308 of file se3.hpp.

◆ operator*=()

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

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

Definition at line 360 of file se3.hpp.

◆ operator=() [1/2]

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

Assignment operator.

◆ operator=() [2/2]

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

Assignment-like operator from OtherDerived.

Definition at line 299 of file se3.hpp.

◆ params()

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

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.

Definition at line 403 of file se3.hpp.

◆ rotationMatrix()

template<class Derived >
SOPHUS_FUNC Matrix3<Scalar> Sophus::SE3Base< Derived >::rotationMatrix ( ) const
inline

Returns rotation matrix.

Definition at line 367 of file se3.hpp.

◆ setQuaternion()

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

Takes in quaternion, and normalizes it.

Precondition: The quaternion must not be close to zero.

Definition at line 383 of file se3.hpp.

◆ setRotationMatrix()

template<class Derived >
SOPHUS_FUNC void Sophus::SE3Base< Derived >::setRotationMatrix ( Matrix3< Scalar > const &  R)
inline

Sets so3 using rotation_matrix.

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

Definition at line 391 of file se3.hpp.

◆ so3() [1/2]

template<class Derived >
SOPHUS_FUNC SO3Type& Sophus::SE3Base< Derived >::so3 ( )
inline

Mutator of SO3 group.

Definition at line 371 of file se3.hpp.

◆ so3() [2/2]

template<class Derived >
SOPHUS_FUNC SO3Type const& Sophus::SE3Base< Derived >::so3 ( ) const
inline

Accessor of SO3 group.

Definition at line 375 of file se3.hpp.

◆ translation() [1/2]

template<class Derived >
SOPHUS_FUNC TranslationType& Sophus::SE3Base< Derived >::translation ( )
inline

Mutator of translation vector.

Definition at line 411 of file se3.hpp.

◆ translation() [2/2]

template<class Derived >
SOPHUS_FUNC TranslationType const& Sophus::SE3Base< Derived >::translation ( ) const
inline

Accessor of translation vector

Definition at line 417 of file se3.hpp.

◆ unit_quaternion()

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

Accessor of unit quaternion.

Definition at line 423 of file se3.hpp.

Member Data Documentation

◆ DoF

template<class Derived >
constexpr int Sophus::SE3Base< Derived >::DoF = 6
staticconstexpr

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

Definition at line 67 of file se3.hpp.

◆ N

template<class Derived >
constexpr int Sophus::SE3Base< Derived >::N = 4
staticconstexpr

Group transformations are 4x4 matrices.

Definition at line 72 of file se3.hpp.

◆ num_parameters

template<class Derived >
constexpr int Sophus::SE3Base< Derived >::num_parameters = 7
staticconstexpr

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

Definition at line 70 of file se3.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