Public Types | Public Member Functions | Public Attributes | Private Attributes | Friends
ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type > Class Template Reference

Representation for a 3D pose (6 degrees of freedom). More...

#include <legacy_pose3d.hpp>

List of all members.

Public Types

typedef
ecl::linear_algebra::Matrix
< Float, 3, 3 > 
RotationMatrix
 The type used to represent rotation matrices.
typedef
ecl::linear_algebra::Matrix
< Float, 3, 1 > 
Translation
 The type used to represent translations.

Public Member Functions

LegacyPose3D< Float > inverse () const
 Calculate the inverse pose.
 LegacyPose3D ()
 Initialise with zero rotation and zero translation.
template<typename Rot , typename Trans >
 LegacyPose3D (const ecl::linear_algebra::EigenBase< Rot > &rotation, const ecl::linear_algebra::EigenBase< Trans > &translation)
 Initialise with rotation matrix and translation.
template<enum Pose2DStorageType Storage_>
 LegacyPose3D (const LegacyPose2D< Float, Storage_ > &pose)
 Initialise from a 2D pose.
template<typename Trans >
 LegacyPose3D (const ecl::linear_algebra::AngleAxis< Float > &angle_axis, const ecl::linear_algebra::MatrixBase< Trans > &translation)
 Initialise from an eigen AngleAxis and a translation.
template<typename Trans >
 LegacyPose3D (const ecl::linear_algebra::Quaternion< Float > &quaternion, const ecl::linear_algebra::MatrixBase< Trans > &translation)
 Initialise from an eigen Quaternion and a translation.
 LegacyPose3D (const LegacyPose3D< Float > &pose)
 Copy constructor for 3d poses.
template<typename Float_ >
LegacyPose3D< Float > operator* (const LegacyPose3D< Float_ > &pose) const
 Combine this pose with the incoming pose.
template<typename Float_ >
LegacyPose3D< Float > & operator*= (const LegacyPose3D< Float_ > &pose)
 Transform this pose by the specified input pose.
template<enum Pose2DStorageType Storage_>
LegacyPose3D< Float > & operator= (const LegacyPose2D< Float, Storage_ > &pose)
 Assign from another Pose2D instance.
LegacyPose3D< Float > & operator= (const LegacyPose3D< Float > &pose)
 Assign from another Pose2D instance.
template<typename Float_ >
LegacyPose3D< Float > relative (const LegacyPose3D< Float_ > &pose) const
 Relative pose between this pose and another.
void rotation (const RotationMatrix &rotation)
 Set the rotational component.
RotationMatrixrotation ()
const RotationMatrixrotation () const
 Return a mutable handle to the translation vector.
RotationMatrix rotationMatrix () const
 Return a const handle to the translation vector.
template<typename Trans >
void translation (const ecl::linear_algebra::MatrixBase< Trans > &translation)
 Set the translation vector.
Translationtranslation ()
 Return a mutable handle to the rotational storage component.
const Translationtranslation () const
 Return a const handle to the rotational storage component.
virtual ~LegacyPose3D ()

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW
typedef Float 
Scalar
 Eigen style declaration of the element type.

Private Attributes

RotationMatrix rot
Translation trans

Friends

template<typename OutputStream , typename Float_ >
OutputStream & operator<< (OutputStream &ostream, const LegacyPose3D< Float_ > &pose)
 Insertion operator for output streams.

Detailed Description

template<typename Float>
class ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >

Representation for a 3D pose (6 degrees of freedom).

This represents a transformation typical of that of an object in 3D, that is, it has 3 translational degrees of freedom and 3 rotational degrees of freedom. Default storage type for rotations is the rotation matrix. We may think about a quaternion storage type in the future.

Template Parameters:
Float: must be a float type (e.g. float, double, float32, float64)

Definition at line 60 of file legacy_pose3d.hpp.


Member Typedef Documentation

template<typename Float >
typedef ecl::linear_algebra::Matrix<Float,3,3> ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::RotationMatrix

The type used to represent rotation matrices.

Definition at line 71 of file legacy_pose3d.hpp.

template<typename Float >
typedef ecl::linear_algebra::Matrix<Float,3,1> ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::Translation

The type used to represent translations.

Definition at line 72 of file legacy_pose3d.hpp.


Constructor & Destructor Documentation

template<typename Float >
ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::LegacyPose3D ( ) [inline]

Initialise with zero rotation and zero translation.

Definition at line 80 of file legacy_pose3d.hpp.

template<typename Float >
template<typename Rot , typename Trans >
ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::LegacyPose3D ( const ecl::linear_algebra::EigenBase< Rot > &  rotation,
const ecl::linear_algebra::EigenBase< Trans > &  translation 
) [inline]

Initialise with rotation matrix and translation.

This accepts arbitrary eigen types to use as a rotation matrix and translation vector.

Parameters:
rotation: 3x3 rotation matrix.
translation: 3x1 translation vector (will compile error if incorrect size).
Template Parameters:
Rot: any compatible eigen 3x3 matrix type (e.g. Matrix<Float,3,3>).
Trans: any compatible eigen 3x1 matrix type (e.g. Matrix<Float,3,1>).

Definition at line 95 of file legacy_pose3d.hpp.

template<typename Float >
template<enum Pose2DStorageType Storage_>
ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::LegacyPose3D ( const LegacyPose2D< Float, Storage_ > &  pose) [inline]

Initialise from a 2D pose.

Essentially converts the 2D pose to a 3D pose, note that any 2D pose object will do.

Parameters:
pose: the 2d pose.

Definition at line 107 of file legacy_pose3d.hpp.

template<typename Float >
template<typename Trans >
ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::LegacyPose3D ( const ecl::linear_algebra::AngleAxis< Float > &  angle_axis,
const ecl::linear_algebra::MatrixBase< Trans > &  translation 
) [inline]

Initialise from an eigen AngleAxis and a translation.

Parameters:
angle_axis: a 3d vector and scalar angle object from eigen.
translation: 3x1 translation vector (will compile error if incorrect size).
Template Parameters:
Trans: any compatible eigen 3x1 matrix type (e.g. Matrix<Float,3,1>).

Definition at line 123 of file legacy_pose3d.hpp.

template<typename Float >
template<typename Trans >
ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::LegacyPose3D ( const ecl::linear_algebra::Quaternion< Float > &  quaternion,
const ecl::linear_algebra::MatrixBase< Trans > &  translation 
) [inline]

Initialise from an eigen Quaternion and a translation.

Parameters:
quaternion: an eigen quaternion object.
translation: 3x1 translation vector (will compile error if incorrect size).
Template Parameters:
Trans: any compatible eigen 3x1 matrix type (e.g. Matrix<Float,3,1>).

Definition at line 137 of file legacy_pose3d.hpp.

template<typename Float >
ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::LegacyPose3D ( const LegacyPose3D< Float > &  pose) [inline]

Copy constructor for 3d poses.

Parameters:
pose: the pose to be copied.

Definition at line 146 of file legacy_pose3d.hpp.

template<typename Float >
virtual ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::~LegacyPose3D ( ) [inline, virtual]

Definition at line 151 of file legacy_pose3d.hpp.


Member Function Documentation

template<typename Float >
LegacyPose3D<Float> ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::inverse ( ) const [inline]

Calculate the inverse pose.

This calculates the reverse transformation between frames.

Returns:
Pose3D : the inverse pose with target and reference frames swapped.

Definition at line 240 of file legacy_pose3d.hpp.

template<typename Float >
template<typename Float_ >
LegacyPose3D<Float> ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::operator* ( const LegacyPose3D< Float_ > &  pose) const [inline]

Combine this pose with the incoming pose.

Parameters:
pose: differential (wrt this pose's frame).
Returns:
Pose3D<Float> : new instance representing the product of the poses.

Definition at line 252 of file legacy_pose3d.hpp.

template<typename Float >
template<typename Float_ >
LegacyPose3D<Float>& ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::operator*= ( const LegacyPose3D< Float_ > &  pose) [inline]

Transform this pose by the specified input pose.

Parameters:
pose: a pose differential (wrt this pose's frame).
Returns:
Pose3D<Float>& : handle to the updated pose (wrt common/global frame).

Definition at line 265 of file legacy_pose3d.hpp.

template<typename Float >
template<enum Pose2DStorageType Storage_>
LegacyPose3D<Float>& ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::operator= ( const LegacyPose2D< Float, Storage_ > &  pose) [inline]

Assign from another Pose2D instance.

Parameters:
pose: another Pose2D, storage type is irrelevant.
Returns:
Pose2D<Float>& : reference handle to this object.

Definition at line 162 of file legacy_pose3d.hpp.

template<typename Float >
LegacyPose3D<Float>& ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::operator= ( const LegacyPose3D< Float > &  pose) [inline]

Assign from another Pose2D instance.

Parameters:
pose: another Pose2D, storage type is irrelevant.
Returns:
Pose2D<Float>& : reference handle to this object.

Definition at line 176 of file legacy_pose3d.hpp.

template<typename Float >
template<typename Float_ >
LegacyPose3D<Float> ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::relative ( const LegacyPose3D< Float_ > &  pose) const [inline]

Relative pose between this pose and another.

Evaluates and returns the pose of this pose, relative to the specified pose.

Parameters:
pose: reference frame for the relative pose.
Returns:
Pose3D<Float> : new instance representing the relative.

Definition at line 279 of file legacy_pose3d.hpp.

template<typename Float >
void ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::rotation ( const RotationMatrix rotation) [inline]

Set the rotational component.

This accepts a rotation matrix to set the rotational part of the pose.

Parameters:
rotation: input rotation to set.

Definition at line 191 of file legacy_pose3d.hpp.

template<typename Float >
RotationMatrix& ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::rotation ( ) [inline]

Definition at line 217 of file legacy_pose3d.hpp.

template<typename Float >
const RotationMatrix& ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::rotation ( ) const [inline]

Return a mutable handle to the translation vector.

>

Definition at line 219 of file legacy_pose3d.hpp.

template<typename Float >
RotationMatrix ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::rotationMatrix ( ) const [inline]

Return a const handle to the translation vector.

>Representation of the rotation in matrix form.

Definition at line 228 of file legacy_pose3d.hpp.

template<typename Float >
template<typename Trans >
void ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::translation ( const ecl::linear_algebra::MatrixBase< Trans > &  translation) [inline]

Set the translation vector.

This accepts an arbitrary eigen types to use as a translation vector. Eigen will emit the appropriate compile time error if it is incompatible.

Parameters:
translation: 3x1 translation vector.
Template Parameters:
Trans: any compatible eigen 3x1 matrix type (e.g. Matrix<Float,3,1>).

Definition at line 204 of file legacy_pose3d.hpp.

template<typename Float >
Translation& ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::translation ( ) [inline]

Return a mutable handle to the rotational storage component.

>

Definition at line 218 of file legacy_pose3d.hpp.

template<typename Float >
const Translation& ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::translation ( ) const [inline]

Return a const handle to the rotational storage component.

>

Definition at line 220 of file legacy_pose3d.hpp.


Friends And Related Function Documentation

template<typename Float >
template<typename OutputStream , typename Float_ >
OutputStream& operator<< ( OutputStream &  ostream,
const LegacyPose3D< Float_ > &  pose 
) [friend]

Insertion operator for output streams.

Note that the output heading angle is formatted in degrees.

Parameters:
ostream: stream satisfying the ecl stream concept.
pose: the inserted pose.
Returns:
OutputStream : the returning stream handle.

Definition at line 309 of file legacy_pose3d.hpp.


Member Data Documentation

template<typename Float >
RotationMatrix ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::rot [private]

Definition at line 292 of file legacy_pose3d.hpp.

template<typename Float >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Float ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::Scalar

Eigen style declaration of the element type.

Definition at line 70 of file legacy_pose3d.hpp.

template<typename Float >
Translation ecl::LegacyPose3D< Float, enable_if< is_float< Float > >::type >::trans [private]

Definition at line 293 of file legacy_pose3d.hpp.


The documentation for this class was generated from the following file:


ecl_geometry
Author(s): Daniel Stonier
autogenerated on Thu Jun 6 2019 21:17:52