Transforms

struct InvalidEulerAxesException : public exception

Exception thrown when using an invalid Euler axes order, e.g., when providing an invalid uint8_t.

struct InvalidTransformException : public motion3d::MessageException

Exception thrown when performing operations including non-unsafe and invalid transforms.

struct InvalidTransformTypeException : public exception

Exception thrown when using an invalid transform type, e.g., when providing an invalid char.

struct InvalidTypeSizeException : public exception

Exception thrown when a transform is created from binary or vector data of the wrong size.

enum class motion3d::EulerAxes : std::uint8_t

Enumerate of all available Euler axes orders.

Values:

enumerator kSXYZ
enumerator kSXYX
enumerator kSXZY
enumerator kSXZX
enumerator kSYZX
enumerator kSYZY
enumerator kSYXZ
enumerator kSYXY
enumerator kSZXY
enumerator kSZXZ
enumerator kSZYX
enumerator kSZYZ
enumerator kRZYX
enumerator kRXYX
enumerator kRYZX
enumerator kRXZX
enumerator kRXZY
enumerator kRYZY
enumerator kRZXY
enumerator kRYXY
enumerator kRYXZ
enumerator kRZXZ
enumerator kRXYZ
enumerator kRZYZ
enum class motion3d::TransformType

Transformation representation type.

Values:

enumerator kAxisAngle
enumerator kDualQuaternion
enumerator kEuler
enumerator kMatrix
enumerator kQuaternion
class TransformInterface

Interface class for generic access to transformations.

Subclassed by motion3d::TransformBase< Derived >, motion3d::TransformBase< AxisAngleTransform >, motion3d::TransformBase< DualQuaternionTransform >, motion3d::TransformBase< EulerTransform >, motion3d::TransformBase< MatrixTransform >, motion3d::TransformBase< QuaternionTransform >

Public Functions

DEFINE_POINTERS(TransformInterface)
virtual ~TransformInterface() = default
inline TransformInterface::Ptr copy() const

Constructs and initializes a copy of *this.

inline TransformInterface::Ptr setIdentity()

Set *this to an identity transform.

inline TransformInterface::Ptr identity() const

Constructs and initializes an identity transform with the same type as *this.

virtual TransformType getType() const = 0
Returns:

the transform type of *this.

virtual bool isType(const TransformType &type) const = 0
Returns:

if the transform type of *this is type.

virtual TransformInterface::Ptr asType(const TransformType &type) const = 0

Converts *this to transform type type.

template<typename T>
std::shared_ptr<T> asType() const

Converts *this to transform type T.

inline TransformInterface::Ptr inverse_()

Inplace variant of inverse().

inline TransformInterface::Ptr inverse() const
Returns:

the inverse transform to *this.

inline TransformInterface::Ptr normalized_()

Inplace variant of normalized().

inline TransformInterface::Ptr normalized() const

Normalizes *this to a valid transform and sets unsafe to false.

inline TransformInterface::Ptr scaleTranslation_(double factor)

Inplace variant of scaleTranslation().

inline TransformInterface::Ptr scaleTranslation(double factor) const

Scales the translation by factor.

inline virtual TransformInterface::Ptr applyPre_(const TransformInterface::ConstPtr &other)

Inplace variant of applyPre(const TransformInterface::ConstPtr&).

inline virtual TransformInterface::Ptr applyPre(const TransformInterface::ConstPtr &other) const

Applies other transform T_\mathrm{o} before *this transform T:

T_\mathrm{o} \circ T

inline virtual TransformInterface::Ptr applyPost_(const TransformInterface::ConstPtr &other)

Inplace variant of applyPost(const TransformInterface::ConstPtr&).

inline virtual TransformInterface::Ptr applyPost(const TransformInterface::ConstPtr &other) const

Applies other transform T_\mathrm{o} after *this transform T:

T \circ T_\mathrm{o}

virtual TransformInterface::Ptr applyPre_(const TransformInterface &other) = 0

Inplace variant of applyPre(const TransformInterface&).

virtual TransformInterface::Ptr applyPre(const TransformInterface &other) const = 0

virtual TransformInterface::Ptr applyPost_(const TransformInterface &other) = 0

Inplace variant of applyPost(const TransformInterface&).

virtual TransformInterface::Ptr applyPost(const TransformInterface &other) const = 0

virtual Eigen::Matrix<double, 3, 1> transformPoint(const Eigen::Ref<const Eigen::Matrix<double, 3, 1>> &point) const = 0

Applies *this on 3D point.

virtual Eigen::Matrix<double, 3, Eigen::Dynamic> transformCloud(const Eigen::Ref<const Eigen::Matrix<double, 3, Eigen::Dynamic>> &cloud) const = 0

Applies *this on 3D point cloud.

virtual std::vector<std::uint8_t> toBinary() const = 0

Converts *this to a binary vector.

virtual std::vector<double> toVector() const = 0

Converts *this to an std vector.

virtual Eigen::Matrix<double, Eigen::Dynamic, 1> toEigenVector() const = 0

Converts *this to an Eigen vector.

virtual bool isUnsafe() const = 0
Returns:

if *this is marked unsafe, meaning that the validity check is skipped at each operation.

virtual bool isValid() const = 0
Returns:

if *this is valid using a default eps for isValid(double) const.

virtual bool isValid(double eps) const = 0
Returns:

if *this is valid w.r.t the threshold eps.

virtual bool isEqual(const TransformInterface::ConstPtr &other) const = 0
Returns:

if *this is equal to other using a default eps for isEqual(const TransformInterface::ConstPtr&, double) const.

virtual bool isEqual(const TransformInterface::ConstPtr &other, double eps) const = 0
Returns:

if *this is equal to other w.r.t the threshold eps.

virtual double rotationNorm() const = 0
Returns:

the rotation norm in rad.

virtual double translationNorm() const = 0
Returns:

the translation norm.

virtual std::string desc() const = 0
Returns:

a description of *this.

virtual std::ostream &stream(std::ostream &os) const = 0

Inserts a description of *this.

Public Static Functions

template<typename ...Args>
static TransformInterface::Ptr Factory(const TransformType &type, Args&&... args)

Constructs and initializes a transform of TransformType type.

Throws:

InvalidTypeSizeException – for an invalid vector size.

Private Functions

virtual TransformInterface::Ptr copyImpl() const = 0
virtual TransformInterface::Ptr setIdentityImpl() = 0
virtual TransformInterface::Ptr identityImpl() const = 0
virtual TransformInterface::Ptr inverseImpl_() = 0
virtual TransformInterface::Ptr inverseImpl() const = 0
virtual TransformInterface::Ptr normalizedImpl_() = 0
virtual TransformInterface::Ptr normalizedImpl() const = 0
virtual TransformInterface::Ptr scaleTranslationImpl_(double factor) = 0
virtual TransformInterface::Ptr scaleTranslationImpl(double factor) const = 0
virtual TransformInterface::Ptr applyPreImpl_(const TransformInterface::ConstPtr &other) = 0
virtual TransformInterface::Ptr applyPreImpl(const TransformInterface::ConstPtr &other) const = 0
virtual TransformInterface::Ptr applyPostImpl_(const TransformInterface::ConstPtr &other) = 0
virtual TransformInterface::Ptr applyPostImpl(const TransformInterface::ConstPtr &other) const = 0
class AxisAngleTransform : public motion3d::TransformBase<AxisAngleTransform>

Axis-angle transformation consisting of a translation vector, a rotation axis and a rotation angle around this axis.

For representing a valid spatial transformation, the rotation axis must have unit length. An unsafe transform means that the validity check, usually performed at each operation, is skipped.

Public Functions

DEFINE_POINTERS(AxisAngleTransform)
AxisAngleTransform()

Constructs and initializes an AxisAngleTransform as identity transform.

template<typename Derived>
AxisAngleTransform(const Eigen::DenseBase<Derived> &translation, Eigen::AngleAxis<double> angle_axis, bool unsafe = false)

Constructs and initializes an AxisAngleTransform from translation vector and axis-angle rotation angle_axis.

template<typename DerivedTrans, typename DerivedAxis>
AxisAngleTransform(const Eigen::DenseBase<DerivedTrans> &translation, double angle, const Eigen::MatrixBase<DerivedAxis> &axis, bool unsafe = false)

Constructs and initializes an AxisAngleTransform from translation vector, rotation angle in rad, and rotation axis.

explicit AxisAngleTransform(const std::vector<std::uint8_t> &binary, bool unsafe = false)

Constructs and initializes an AxisAngleTransform from binary data.

Throws:

InvalidTypeSizeException – for an invalid binary size.

explicit AxisAngleTransform(const std::vector<double> &vector, bool unsafe = false)

Constructs and initializes an AxisAngleTransform from vector data.

Throws:

InvalidTypeSizeException – for an invalid vector size.

template<typename Derived>
explicit AxisAngleTransform(const Eigen::DenseBase<Derived> &matrix, bool unsafe = false)

Constructs and initializes an AxisAngleTransform from an Eigen vector matrix.

Throws:

InvalidTypeSizeException – for an invalid matrix size.

inline AxisAngleTransform copy() const

Create a copy of *this.

AxisAngleTransform &setIdentity()

Set *this to an identity transform.

virtual std::vector<double> toVector() const override

Converts *this to an std vector.

virtual Eigen::Matrix<double, Eigen::Dynamic, 1> toEigenVector() const override

Converts *this to an Eigen vector.

template<class T>
T asType() const

Converts *this to transform type T.

virtual bool isValid(double eps) const override

Checks if *this is valid w.r.t.

the threshold eps.

AxisAngleTransform &inverse_()

Inplace variant of inverse().

AxisAngleTransform inverse() const
Returns:

the inverse transform to *this.

AxisAngleTransform &normalized_()

Inplace variant of normalized().

AxisAngleTransform normalized() const

Normalizes *this to a valid axis-angle transform and sets unsafe to false.

AxisAngleTransform &scaleTranslation_(double factor)

Inplace variant of scaleTranslation().

AxisAngleTransform scaleTranslation(double factor) const

Scales the translation by factor.

template<class T>
AxisAngleTransform &applyPre_(const T &other)

Inplace variant of applyPre().

template<class T>
AxisAngleTransform applyPre(const T &other) const

Applies other transform T_\mathrm{o} before *this transform T:

T_\mathrm{o} \circ T

template<class T>
AxisAngleTransform &applyPost_(const T &other)

Inplace variant of applyPost().

template<class T>
AxisAngleTransform applyPost(const T &other) const

Applies other transform T_\mathrm{o} after *this transform T:

T \circ T_\mathrm{o}

template<typename Derived>
Eigen::Matrix<double, 3, 1> transformPoint(const Eigen::MatrixBase<Derived> &point) const

Applies *this on 3D point.

template<typename Derived>
Eigen::Matrix<double, 3, Derived::ColsAtCompileTime> transformCloud(const Eigen::MatrixBase<Derived> &cloud) const

Applies *this on 3D point cloud.

virtual double rotationNorm() const override
Returns:

the rotation norm in rad.

virtual double translationNorm() const override
Returns:

the translation norm.

inline const Eigen::Matrix<double, 3, 1> &getTranslation() const
Returns:

the translation vector.

inline const Eigen::AngleAxis<double> &getAngleAxis() const
Returns:

the angle-axis rotation.

inline double getAngle() const
Returns:

the rotation angle in rad.

inline const Eigen::Matrix<double, 3, 1> &getAxis() const
Returns:

the rotation axis.

template<typename Derived>
AxisAngleTransform &setTranslation(const Eigen::MatrixBase<Derived> &translation, bool unsafe = false)

Sets the translation vector.

AxisAngleTransform &setAngleAxis(const Eigen::AngleAxis<double> &angle_axis, bool unsafe = false)

Sets the angle-axis rotation.

AxisAngleTransform &setAngle(const double &angle, bool unsafe = false)

Sets the rotation angle in rad.

template<typename Derived>
AxisAngleTransform &setAxis(const Eigen::MatrixBase<Derived> &axis, bool unsafe = false)

Sets the rotation axis.

inline virtual std::string desc() const override
Returns:

a description of *this.

virtual std::ostream &stream(std::ostream &os) const override

Inserts a description of *this.

template<class T>
AxisAngleTransform &operator*=(const T &other)

Applies other after *this.

template<class T>
AxisAngleTransform &operator/=(const T &other)

Applies the inverse of other after *this.

Public Static Functions

template<typename Derived>
static bool isUnitAxis(const Eigen::MatrixBase<Derived> &axis, double eps)

Checks if axis is unit w.r.t.

the threshold eps.

Private Members

Eigen::Matrix<double, 3, 1> translation_

Translation vector.

Eigen::AngleAxis<double> angle_axis_

Angle-axis rotation.

class DualQuaternionTransform : public motion3d::TransformBase<DualQuaternionTransform>

Transformation consisting of a unit DualQuaternion \mathcal{Q}=\mathrm{r} + \epsilon \, \mathrm{d}.

For representing a valid spatial transformation, the dual quaternion must be unit, i.e., ||\mathrm{r}|| = 1 and \mathrm{r}^{\ast} \, \mathrm{d} + \mathrm{d}^{\ast} \, \mathrm{r} = 0. An unsafe transform means that the validity check, usually performed at each operation, is skipped.

Operations:

  • Concatenation: \mathcal{Q}_{ac} = \mathcal{Q}_{ab} \mathcal{Q}_{bc}

  • Inversion: V^{-1} \equiv \mathcal{Q}^{\ast}

  • Point transformation: (1 + \epsilon \, \{ 0, \boldsymbol{p}_a \} ) = \mathcal{Q}_{ab} ( 1 + \epsilon \, \{ 0, \boldsymbol{p}_b \} ) \ \bar{\mathcal{Q}}_{ab}^{*}

Public Functions

DEFINE_POINTERS(DualQuaternionTransform)
DualQuaternionTransform()

Constructs and initializes a DualQuaternionTransform as identity transform.

explicit DualQuaternionTransform(DualQuaternion<double> dq, bool unsafe = false)

Constructs and initializes a DualQuaternionTransform from dual quaternion dq.

DualQuaternionTransform(const Quaternion<double> &real, const Quaternion<double> &dual, bool unsafe = false)

Constructs and initializes a DualQuaternionTransform from real and dual part.

template<typename DerivedReal, typename DerivedDual>
DualQuaternionTransform(const Eigen::DenseBase<DerivedReal> &real, const Eigen::DenseBase<DerivedDual> &dual, bool unsafe = false)

Constructs and initializes a DualQuaternionTransform from real and dual part Eigen matrices.

explicit DualQuaternionTransform(const std::vector<std::uint8_t> &binary, bool unsafe = false)

Constructs and initializes a DualQuaternionTransform from binary data.

Throws:

InvalidTypeSizeException – for an invalid binary size.

explicit DualQuaternionTransform(const std::vector<double> &vector, bool unsafe = false)

Constructs and initializes a DualQuaternionTransform from vector data.

Throws:

InvalidTypeSizeException – for an invalid vector size.

template<typename Derived>
explicit DualQuaternionTransform(const Eigen::DenseBase<Derived> &matrix, bool unsafe = false)

Constructs and initializes a DualQuaternionTransform from an Eigen vector matrix.

Throws:

InvalidTypeSizeException – for an invalid matrix size.

inline DualQuaternionTransform copy() const

Create a copy of *this.

DualQuaternionTransform &setIdentity()

Set *this to an identity transform.

virtual std::vector<double> toVector() const override

Converts *this to an std vector.

virtual Eigen::Matrix<double, Eigen::Dynamic, 1> toEigenVector() const override

Converts *this to an Eigen vector.

template<class T>
T asType() const

Converts *this to transform type T.

virtual bool isValid(double eps) const override

Checks if *this is valid w.r.t.

the threshold eps.

DualQuaternionTransform &inverse_()

Inplace variant of inverse().

DualQuaternionTransform inverse() const
Returns:

the inverse transform to *this.

DualQuaternionTransform &normalized_()

Inplace variant of normalized().

DualQuaternionTransform normalized() const

Normalizes *this to a valid dual quaternion transform and sets unsafe to false.

DualQuaternionTransform &scaleTranslation_(double factor)

Inplace variant of scaleTranslation().

DualQuaternionTransform scaleTranslation(double factor) const

Scales the translation by factor.

template<class T>
DualQuaternionTransform &applyPre_(const T &other)

Inplace variant of applyPre().

template<class T>
DualQuaternionTransform applyPre(const T &other) const

Applies other transform T_\mathrm{o} before *this transform T:

T_\mathrm{o} \circ T

template<class T>
DualQuaternionTransform &applyPost_(const T &other)

Inplace variant of applyPost().

template<class T>
DualQuaternionTransform applyPost(const T &other) const

Applies other transform T_\mathrm{o} after *this transform T:

T \circ T_\mathrm{o}

template<typename Derived>
Eigen::Matrix<double, 3, 1> transformPoint(const Eigen::MatrixBase<Derived> &point) const

Applies *this on 3D point.

template<typename Derived>
Eigen::Matrix<double, 3, Derived::ColsAtCompileTime> transformCloud(const Eigen::MatrixBase<Derived> &cloud) const

Applies *this on 3D point cloud.

virtual double rotationNorm() const override
Returns:

the rotation norm in rad.

virtual double translationNorm() const override
Returns:

the translation norm.

inline const DualQuaternion<double> &getDualQuaternion() const
Returns:

the dual quaternion.

inline const Quaternion<double> &getReal() const
Returns:

the real part.

inline const Quaternion<double> &getDual() const
Returns:

the dual part.

DualQuaternionTransform &setDualQuaternion(const DualQuaternion<double> &dq, bool unsafe = false)

Sets the dual quaternion.

DualQuaternionTransform &setReal(const Quaternion<double> &real, bool unsafe = false)

Sets the real part.

DualQuaternionTransform &setDual(const Quaternion<double> &dual, bool unsafe = false)

Sets the dual part.

inline virtual std::string desc() const override
Returns:

a description of *this.

virtual std::ostream &stream(std::ostream &os) const override

Inserts a description of *this.

template<class T>
DualQuaternionTransform &operator*=(const T &other)

Applies other after *this.

template<class T>
DualQuaternionTransform &operator/=(const T &other)

Applies the inverse of other after *this.

Public Static Functions

static bool isUnitDualQuaternion(const Quaternion<double> &real, const Quaternion<double> &dual, double eps)

Checks if dual quaternion with real and dual parts is unit w.r.t.

the threshold eps.

Private Members

DualQuaternion<double> dq_

Dual quaternion.

class EulerTransform : public motion3d::TransformBase<EulerTransform>

Euler transformation consisting of a translation vector and Euler rotation angles around three axes in a configurable order.

All possible orders are defined in the motion3d::EulerAxes enumerate. Since the Euler angles are not subject to any constraints, they are always valid.

Public Functions

DEFINE_POINTERS(EulerTransform)
EulerTransform()

Constructs and initializes an EulerTransform as identity transform.

EulerTransform(const AxisAngleTransform &obj, EulerAxes axes)

Constructs and initializes an EulerTransform from AxisAngleTransform obj with specific Euler axes order.

EulerTransform(const DualQuaternionTransform &obj, EulerAxes axes)

Constructs and initializes an EulerTransform from DualQuaternionTransform obj with specific Euler axes order.

EulerTransform(const EulerTransform &obj, EulerAxes axes)

Constructs and initializes an EulerTransform from EulerTransform obj with specific Euler axes order.

EulerTransform(const MatrixTransform &obj, EulerAxes axes)

Constructs and initializes an EulerTransform from MatrixTransform obj with specific Euler axes order.

EulerTransform(const QuaternionTransform &obj, EulerAxes axes)

Constructs and initializes an EulerTransform from QuaternionTransform obj with specific Euler axes order.

template<typename Derived>
EulerTransform(const Eigen::DenseBase<Derived> &translation, double ai, double aj, double ak, EulerAxes axes = kEulerAxesDefault, bool unsafe = false)

Constructs and initializes an EulerTransform from a translation vector, separate rotation angles in rad, and Euler axes order.

template<typename DerivedTrans, typename DerivedAngles>
EulerTransform(const Eigen::DenseBase<DerivedTrans> &translation, const Eigen::DenseBase<DerivedAngles> &angles, EulerAxes axes = kEulerAxesDefault, bool unsafe = false)

Constructs and initializes an EulerTransform from a translation vector, rotation angles in rad, and Euler axes order.

explicit EulerTransform(const std::vector<std::uint8_t> &binary, bool unsafe = false)

Constructs and initializes an EulerTransform from binary data.

Throws:

InvalidTypeSizeException – for an invalid binary size.

explicit EulerTransform(const std::vector<double> &vector, bool unsafe = false)

Constructs and initializes an EulerTransform from vector data.

Throws:

InvalidTypeSizeException – for an invalid vector size.

template<typename Derived>
explicit EulerTransform(const Eigen::DenseBase<Derived> &matrix, bool unsafe = false)

Constructs and initializes an EulerTransform from an Eigen vector matrix.

Throws:

InvalidTypeSizeException – for an invalid matrix size.

inline EulerTransform copy() const

Create a copy of *this.

EulerTransform &setIdentity()

Set *this to an identity transform.

virtual std::vector<double> toVector() const override

Converts *this to an std vector.

virtual Eigen::Matrix<double, Eigen::Dynamic, 1> toEigenVector() const override

Converts *this to an Eigen vector.

template<class T>
T asType() const

Converts *this to transform type T.

virtual bool isValid(double eps) const override

Checks if *this is valid w.r.t.

the threshold eps.

EulerTransform &changeAxes_(EulerAxes axes)

Inplace variant of changeAxes().

EulerTransform changeAxes(EulerAxes axes) const

Change Euler axes order.

EulerTransform &inverse_()

Inplace variant of inverse().

EulerTransform inverse() const
Returns:

the inverse transform to *this.

EulerTransform &normalized_()

Inplace variant of normalized().

EulerTransform normalized() const

Normalizes *this to a valid Euler transform and sets unsafe to false.

EulerTransform &scaleTranslation_(double factor)

Inplace variant of scaleTranslation().

EulerTransform scaleTranslation(double factor) const

Scales the translation by factor.

template<class T>
EulerTransform &applyPre_(const T &other)

Inplace variant of applyPre().

template<class T>
EulerTransform applyPre(const T &other) const

Applies other transform T_\mathrm{o} before *this transform T:

T_\mathrm{o} \circ T

template<class T>
EulerTransform &applyPost_(const T &other)

Inplace variant of applyPost().

template<class T>
EulerTransform applyPost(const T &other) const

Applies other transform T_\mathrm{o} after *this transform T:

T \circ T_\mathrm{o}

template<typename Derived>
Eigen::Matrix<double, 3, 1> transformPoint(const Eigen::MatrixBase<Derived> &point) const

Applies *this on 3D point.

template<typename Derived>
Eigen::Matrix<double, 3, Derived::ColsAtCompileTime> transformCloud(const Eigen::MatrixBase<Derived> &cloud) const

Applies *this on 3D point cloud.

virtual double rotationNorm() const override
Returns:

the rotation norm in rad.

virtual double translationNorm() const override
Returns:

the translation norm.

inline const Eigen::Matrix<double, 3, 1> &getTranslation() const
Returns:

the translation vector.

inline double getAi() const
Returns:

the rotation around axis i in rad.

inline double getAj() const
Returns:

the rotation around axis j in rad.

inline double getAk() const
Returns:

the rotation around axis k in rad.

Eigen::Matrix<double, 3, 1> getAngles() const
Returns:

the rotations around all axes in order [i \ j \ k] in rad as Eigen matrix.

inline EulerAxes getAxes() const
Returns:

the Euler axes order.

template<typename Derived>
EulerTransform &setTranslation(const Eigen::MatrixBase<Derived> &translation, bool unsafe = false)

Sets the translation vector.

EulerTransform &setAi(const double &ai, bool unsafe = false)

Sets the rotation around axis i in rad.

EulerTransform &setAj(const double &aj, bool unsafe = false)

Sets the rotation around axis j in rad.

EulerTransform &setAk(const double &ak, bool unsafe = false)

Sets the rotation around axis k in rad.

template<typename Derived>
EulerTransform &setAngles(const Eigen::MatrixBase<Derived> &angles, bool unsafe = false)

Sets the rotations around all axes in order [i \ j \ k] in rad as Eigen matrix.

EulerTransform &setAxes(const EulerAxes &axes, bool unsafe = false)

Sets the Euler axes order.

inline virtual std::string desc() const override
Returns:

a description of *this.

virtual std::ostream &stream(std::ostream &os) const override

Inserts a description of *this.

template<class T>
EulerTransform &operator*=(const T &other)

Applies other after *this.

template<class T>
EulerTransform &operator/=(const T &other)

Applies the inverse of other after *this.

Private Members

Eigen::Matrix<double, 3, 1> translation_

Translation vector.

double ai_

Rotation around axis i in rad

double aj_

Rotation around axis j in rad

double ak_

Rotation around axis k in rad

EulerAxes axes_

Euler axes order.

class MatrixTransform : public motion3d::TransformBase<MatrixTransform>

Matrix transformation consisting of a homogeneous \mathrm{SE(3)} transformation matrix.

The matrix

\quad \boldsymbol{M} = \begin{bmatrix} \boldsymbol{R} & \boldsymbol{t} \\ \boldsymbol{0} & 1 \end{bmatrix}

consists of the 3x3 rotation matrix \boldsymbol{R} \in \mathrm{SO(3)} and the translation vector \boldsymbol{t}.

For representing a valid spatial transformation, the rotation matrix must be orthogonal and have determinant +1. An unsafe transform means that the validity check, usually performed at each operation, is skipped.

Operations:

  • Concatenation: \mathrm{M}_{ac} = \mathrm{M}_{ab} \mathrm{M}_{bc}

  • Inversion: V^{-1} \equiv \begin{bmatrix} \boldsymbol{R}^\mathrm{T} & - \boldsymbol{R}^\mathrm{T} \boldsymbol{t} \\ \boldsymbol{0} & 1 \end{bmatrix}

  • Point transformation: [\boldsymbol{p}_a \ 1]^\mathrm{T} = \mathrm{M}_{ab} \, [\boldsymbol{p}_b \ 1]^\mathrm{T}

Public Functions

DEFINE_POINTERS(MatrixTransform)
MatrixTransform()

Constructs and initializes a MatrixTransform as identity transform.

MatrixTransform(const Eigen::Matrix<double, 3, 1> &translation, const Eigen::Matrix<double, 3, 3> &rotation_matrix, bool unsafe = false)

Constructs and initializes a MatrixTransform from a translation vector and a \mathrm{SO(3)} rotation_matrix.

explicit MatrixTransform(const std::vector<std::uint8_t> &binary, bool unsafe = false)

Constructs and initializes a MatrixTransform from binary data.

Throws:

InvalidTypeSizeException – for an invalid binary size.

explicit MatrixTransform(const std::vector<double> &vector, bool unsafe = false)

Constructs and initializes a MatrixTransform from vector data.

Throws:

InvalidTypeSizeException – for an invalid vector size.

template<typename Derived>
explicit MatrixTransform(const Eigen::DenseBase<Derived> &matrix, bool unsafe = false)

Constructs and initializes a MatrixTransform from.

  • a homogeneous \mathrm{SE(3)} transformation matrix.

  • the upper 3x4 part of a homogeneous \mathrm{SE(3)} transformation matrix.

  • an Eigen vector matrix.

Throws:

InvalidTypeSizeException – for an invalid size.

inline MatrixTransform copy() const

Create a copy of *this.

MatrixTransform &setIdentity()

Set *this to an identity transform.

virtual std::vector<double> toVector() const override

Converts *this to an std vector.

virtual Eigen::Matrix<double, Eigen::Dynamic, 1> toEigenVector() const override

Converts *this to an Eigen vector.

template<class T>
T asType() const

Converts *this to transform type T.

virtual bool isValid(double eps) const override

Checks if *this is valid w.r.t.

the threshold eps.

MatrixTransform &inverse_()

Inplace variant of inverse().

MatrixTransform inverse() const
Returns:

the inverse transform to *this.

MatrixTransform &normalized_()

Inplace variant of normalized().

MatrixTransform normalized() const

Normalizes *this to a valid matrix transform and sets unsafe to false.

MatrixTransform &scaleTranslation_(double factor)

Inplace variant of scaleTranslation().

MatrixTransform scaleTranslation(double factor) const

Scales the translation by factor.

template<class T>
MatrixTransform &applyPre_(const T &other)

Inplace variant of applyPre().

template<class T>
MatrixTransform applyPre(const T &other) const

Applies other transform T_\mathrm{o} before *this transform T:

T_\mathrm{o} \circ T

template<class T>
MatrixTransform &applyPost_(const T &other)

Inplace variant of applyPost().

template<class T>
MatrixTransform applyPost(const T &other) const

Applies other transform T_\mathrm{o} after *this transform T:

T \circ T_\mathrm{o}

template<typename Derived>
Eigen::Matrix<double, 3, 1> transformPoint(const Eigen::MatrixBase<Derived> &point) const

Applies *this on 3D point.

template<typename Derived>
Eigen::Matrix<double, 3, Derived::ColsAtCompileTime> transformCloud(const Eigen::MatrixBase<Derived> &cloud) const

Applies *this on 3D point cloud.

virtual double rotationNorm() const override
Returns:

the rotation norm in rad.

virtual double translationNorm() const override
Returns:

the translation norm.

inline const Eigen::Matrix<double, 4, 4> &getMatrix() const
Returns:

the homogeneous \mathrm{SE(3)} transformation matrix.

inline Eigen::Matrix<double, 3, 1> getTranslation() const
Returns:

the translation vector.

inline Eigen::Matrix<double, 3, 3> getRotationMatrix() const
Returns:

the \mathrm{SO(3)} rotation matrix.

template<typename Derived>
MatrixTransform &setMatrix(const Eigen::MatrixBase<Derived> &matrix, bool unsafe = false)

Sets the homogeneous \mathrm{SE(3)} transformation matrix.

MatrixTransform &setTranslation(const Eigen::Matrix<double, 3, 1> &translation, bool unsafe = false)

Sets the translation vector.

MatrixTransform &setRotationMatrix(const Eigen::Matrix<double, 3, 3> &rotation_matrix, bool unsafe = false)

Sets the \mathrm{SO(3)} rotation matrix.

inline virtual std::string desc() const override
Returns:

a description of *this.

virtual std::ostream &stream(std::ostream &os) const override

Inserts a description of *this.

template<class T>
MatrixTransform &operator*=(const T &other)

Applies other after *this.

template<class T>
MatrixTransform &operator/=(const T &other)

Applies the inverse of other after *this.

Public Static Functions

template<typename Derived>
static bool isValidMatrix(const Eigen::MatrixBase<Derived> &matrix, double eps)

Checks if matrix is a valid rigid transformation matrix w.r.t.

the threshold eps.

template<typename Derived>
static bool isValidRotationMatrix(const Eigen::MatrixBase<Derived> &matrix, double eps)

Checks if matrix is a valid rotation matrix w.r.t.

the threshold eps.

Private Members

Eigen::Matrix<double, 4, 4> matrix_

Homogeneous \mathrm{SE(3)} transformation matrix.

class QuaternionTransform : public motion3d::TransformBase<QuaternionTransform>

Quaternion transformation consisting of a translation vector \boldsymbol{t} and a rotation Quaternion \mathrm{q}.

For representing a valid spatial transformation, the quaternion must be unit, i.e., ||\mathrm{q}|| = 1. An unsafe transform means that the validity check, usually performed at each operation, is skipped.

Operations:

  • Concatenation: \mathrm{q}_{ac} = \mathrm{q}_{ab} \mathrm{q}_{bc} and \{ 0, \boldsymbol{t}_{ac} \} = \{ 0, \boldsymbol{t}_{ab} \} + \mathrm{q}_{ab} \, \{ 0, \boldsymbol{t}_{bc} \} \, \mathrm{q}_{ab}^{\ast}

  • Inversion: V^{-1}: \mathrm{q}_{\mathrm{inv}} = \mathrm{q}^{\ast} and \{ 0, \boldsymbol{t}_{\mathrm{inv}} \} = \mathrm{q}^{\ast} \, \{ 0, \boldsymbol{t} \} \, \mathrm{q}

  • Point transformation: \{ 0, \boldsymbol{p}_a \} = \mathrm{q}_{ab} \, \{ 0, \boldsymbol{p}_b \} \, \mathrm{q}_{ab}^{\ast} + \{ 0, \boldsymbol{t} \}

Public Functions

DEFINE_POINTERS(QuaternionTransform)
QuaternionTransform()

Constructs and initializes a QuaternionTransform as identity transform.

template<typename Derived>
QuaternionTransform(const Eigen::DenseBase<Derived> &translation, Quaternion<double> quaternion, bool unsafe = false)

Constructs and initializes a QuaternionTransform from a translation vector and a rotation quaternion.

template<typename Derived>
QuaternionTransform(const Eigen::DenseBase<Derived> &translation, const Eigen::Quaternion<double> &quaternion, bool unsafe = false)

Constructs and initializes a QuaternionTransform from a translation vector and a rotation quaternion.

template<typename DerivedTrans, typename DerivedQuat>
QuaternionTransform(const Eigen::DenseBase<DerivedTrans> &translation, const Eigen::DenseBase<DerivedQuat> &quaternion, bool unsafe = false)

Constructs and initializes a QuaternionTransform from a translation vector and a rotation quaternion matrix.

explicit QuaternionTransform(const std::vector<std::uint8_t> &binary, bool unsafe = false)

Constructs and initializes a QuaternionTransform from binary data.

Throws:

InvalidTypeSizeException – for an invalid binary size.

explicit QuaternionTransform(const std::vector<double> &vector, bool unsafe = false)

Constructs and initializes a QuaternionTransform from vector data.

Throws:

InvalidTypeSizeException – for an invalid vector size.

template<typename Derived>
explicit QuaternionTransform(const Eigen::DenseBase<Derived> &matrix, bool unsafe = false)

Constructs and initializes a QuaternionTransform from an Eigen vector matrix.

Throws:

InvalidTypeSizeException – for an invalid matrix size.

inline QuaternionTransform copy() const

Create a copy of *this.

QuaternionTransform &setIdentity()

Set *this to an identity transform.

virtual std::vector<double> toVector() const override

Converts *this to an std vector.

virtual Eigen::Matrix<double, Eigen::Dynamic, 1> toEigenVector() const override

Converts *this to an Eigen vector.

template<class T>
T asType() const

Converts *this to transform type T.

virtual bool isValid(double eps) const override

Checks if *this is valid w.r.t.

the threshold eps.

QuaternionTransform &inverse_()

Inplace variant of inverse().

QuaternionTransform inverse() const
Returns:

the inverse transform to *this.

QuaternionTransform &normalized_()

Inplace variant of normalized().

QuaternionTransform normalized() const

Normalizes *this to a valid quaternion transform and sets unsafe to false.

QuaternionTransform &scaleTranslation_(double factor)

Inplace variant of scaleTranslation().

QuaternionTransform scaleTranslation(double factor) const

Scales the translation by factor.

template<class T>
QuaternionTransform &applyPre_(const T &other)

Inplace variant of applyPre().

template<class T>
QuaternionTransform applyPre(const T &other) const

Applies other transform T_\mathrm{o} before *this transform T:

T_\mathrm{o} \circ T

template<class T>
QuaternionTransform &applyPost_(const T &other)

Inplace variant of applyPost().

template<class T>
QuaternionTransform applyPost(const T &other) const

Applies other transform T_\mathrm{o} after *this transform T:

T \circ T_\mathrm{o}

template<typename Derived>
Eigen::Matrix<double, 3, 1> transformPoint(const Eigen::MatrixBase<Derived> &point) const

Applies *this on 3D point.

template<typename Derived>
Eigen::Matrix<double, 3, Derived::ColsAtCompileTime> transformCloud(const Eigen::MatrixBase<Derived> &cloud) const

Applies *this on 3D point cloud.

virtual double rotationNorm() const override
Returns:

the rotation norm in rad.

virtual double translationNorm() const override
Returns:

the translation norm.

inline const Eigen::Matrix<double, 3, 1> &getTranslation() const
Returns:

the translation vector.

inline const Quaternion<double> &getQuaternion() const
Returns:

the rotation quaternion.

template<typename Derived>
QuaternionTransform &setTranslation(const Eigen::MatrixBase<Derived> &translation, bool unsafe = false)

Sets the translation vector.

QuaternionTransform &setQuaternion(const Quaternion<double> &quaternion, bool unsafe = false)

Sets the rotation quaternion.

inline virtual std::string desc() const override
Returns:

a description of *this.

virtual std::ostream &stream(std::ostream &os) const override

Inserts a description of *this.

template<class T>
QuaternionTransform &operator*=(const T &other)

Applies other after *this.

template<class T>
QuaternionTransform &operator/=(const T &other)

Applies the inverse of other after *this.

Public Static Functions

static bool isUnitQuaternion(const Quaternion<double> &quaternion, double eps)

Checks if quaternion is unit w.r.t.

the threshold eps.

Private Members

Eigen::Matrix<double, 3, 1> translation_

Translation vector.

Quaternion<double> quaternion_

Rotation quaternion.