Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes | Friends | List of all members
ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type > Class Template Reference

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

#include <legacy_pose2d.hpp>

Public Types

typedef geometry::Pose2DMath< Float, RotationAngleStorageRotationAngleMath
 Rotational math specific to rotational angles. More...
 
typedef geometry::Pose2DMath< Float, Storage > RotationMath
 Rotational math specific to this storage type. More...
 
typedef ecl::linear_algebra::Matrix< Float, 2, 2 > RotationMatrix
 The type used to represent rotation matrices. More...
 
typedef geometry::Pose2DMath< Float, RotationMatrixStorageRotationMatrixMath
 Rotational math specific to rotational matrices. More...
 
typedef ecl_traits< LegacyPose2D< Float, Storage, typename enable_if< is_float< Float > >::type > >::RotationType RotationType
 The type used for storage of the rotation/angle. More...
 
typedef ecl::linear_algebra::Matrix< Float, 2, 1 > Translation
 The type used to represent translations. More...
 

Public Member Functions

void heading (const Angle< Float > &value)
 Sets the heading. More...
 
Angle< Float > heading () const
 Get the heading. More...
 
LegacyPose2D< Float, Storage > inverse () const
 Calculate the inverse pose. More...
 
 LegacyPose2D ()
 Default constructor. More...
 
 LegacyPose2D (const Float &x, const Float &y, const Angle< Float > &angle)
 Construct the pose using scalars for position and rotation angle. More...
 
template<typename Rot , typename Trans >
 LegacyPose2D (const ecl::linear_algebra::MatrixBase< Rot > &R, const ecl::linear_algebra::MatrixBase< Trans > &T)
 Construct the pose using a rotation matrix and a translation vector. More...
 
template<typename Trans >
 LegacyPose2D (const Angle< Float > &angle, const ecl::linear_algebra::MatrixBase< Trans > &T)
 Construct the pose using a rotational angle and a translation vector. More...
 
template<enum Pose2DStorageType Storage_>
 LegacyPose2D (const LegacyPose2D< Float, Storage_ > &pose)
 Copy constructor that works for copies from any pose type. More...
 
template<enum Pose2DStorageType Storage_>
LegacyPose2D< Float, Storage > operator* (const LegacyPose2D< Float, Storage_ > &pose) const
 Combine this pose with the incoming pose. More...
 
LegacyPose2D< Float > & operator*= (const LegacyPose2D< Float > &pose)
 Transform this pose by the specified input pose. More...
 
template<enum Pose2DStorageType Storage_>
LegacyPose2D< Float, Storage > & operator= (const LegacyPose2D< Float, Storage_ > &pose)
 Assign from another Pose2D instance. More...
 
template<enum Pose2DStorageType Storage_>
LegacyPose2D< Float, Storage > relative (const LegacyPose2D< Float, Storage_ > &pose) const
 Relative pose between this pose and another. More...
 
void rotation (const Angle< Float > &heading)
 Set the rotational component with a heading angle. More...
 
void rotation (const RotationMatrix &rotation_matrix)
 Set the rotational component with a rotation matrix. More...
 
RotationTyperotation ()
 
const RotationTyperotation () const
 Return a mutable handle to the translation vector. More...
 
template<typename Rot >
void rotationMatrix (const ecl::linear_algebra::MatrixBase< Rot > &rotation_matrix)
 Set the rotational component. More...
 
RotationMatrix rotationMatrix () const
 
void setIdentity ()
 Set this pose to zero rotation and zero translation. More...
 
void setPose (const Float &x, const Float &y, const Angle< Float > &heading)
 Sets the pose with a triplet. More...
 
void translation (const Float &x, const Float &y)
 Set the translation vector from a pair of x,y values. More...
 
template<typename Trans >
void translation (const ecl::linear_algebra::MatrixBase< Trans > &T)
 Set the translation vector. More...
 
Translationtranslation ()
 Return a mutable handle to the rotational storage component. More...
 
const Translationtranslation () const
 Return a const handle to the rotational storage component. More...
 
void x (const Float &value)
 Sets the x-coordinate. More...
 
Float x () const
 Return a const handle to the translation vector. More...
 
void y (const Float &value)
 Sets the y-coordinate. More...
 
Float y () const
 Get the y-coordinate. More...
 
virtual ~LegacyPose2D ()
 

Static Public Member Functions

static LegacyPose2D< Float, Storage > Identity ()
 Static function for returning the idenitity pose, eigen style. More...
 

Public Attributes

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

Private Attributes

RotationType rot
 
Translation trans
 

Friends

template<typename OutputStream , typename Float_ , enum Pose2DStorageType Storage_>
OutputStream & operator<< (OutputStream &ostream, const LegacyPose2D< Float_, Storage_ > &pose)
 Insertion operator for output streams. More...
 

Detailed Description

template<typename Float, enum Pose2DStorageType Storage>
class ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >

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

This represents a transformation typical of that of an object in 2D, e.g. a mobile robot on a horizontal plane. There are two storage types for this object, the default is rotation matrix, but scalar angular storage can be selected by supplying a second template parameter to the type:

LegacyPose2D<double,RotationAngleStorage>
Template Parameters
Float: must be a float type (e.g. float, double, float32, float64)
Storage: type of storage (RotationMatrixStorage, RotationAngleStorage).

Definition at line 183 of file legacy_pose2d.hpp.

Member Typedef Documentation

template<typename Float , enum Pose2DStorageType Storage>
typedef geometry::Pose2DMath<Float,RotationAngleStorage> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::RotationAngleMath

Rotational math specific to rotational angles.

Definition at line 196 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
typedef geometry::Pose2DMath<Float,Storage> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::RotationMath

Rotational math specific to this storage type.

Definition at line 194 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
typedef ecl::linear_algebra::Matrix<Float,2,2> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::RotationMatrix

The type used to represent rotation matrices.

Definition at line 198 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
typedef geometry::Pose2DMath<Float,RotationMatrixStorage> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::RotationMatrixMath

Rotational math specific to rotational matrices.

Definition at line 195 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
typedef ecl_traits< LegacyPose2D<Float,Storage,typename enable_if<is_float<Float> >::type> >::RotationType ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::RotationType

The type used for storage of the rotation/angle.

Definition at line 197 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
typedef ecl::linear_algebra::Matrix<Float,2,1> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::Translation

The type used to represent translations.

Definition at line 199 of file legacy_pose2d.hpp.

Constructor & Destructor Documentation

template<typename Float , enum Pose2DStorageType Storage>
ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::LegacyPose2D ( )
inline

Default constructor.

Initialises the pose with zero rotation and zero translation. Might be worth dropping the setting here (aka eigen style) if we need speed, not safety. If we do so, maybe a debug mode is_initialised flag? Also, if we do so make sure to update the Identity static function.

Definition at line 212 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::LegacyPose2D ( const Float &  x,
const Float &  y,
const Angle< Float > &  angle 
)
inline

Construct the pose using scalars for position and rotation angle.

Parameters
x,y: position (origin) of the target frame
angle: initial heading angle (double is compatible)(radians).

Definition at line 220 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Rot , typename Trans >
ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::LegacyPose2D ( const ecl::linear_algebra::MatrixBase< Rot > &  R,
const ecl::linear_algebra::MatrixBase< Trans > &  T 
)
inline

Construct the pose using a rotation matrix and a translation vector.

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

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

Definition at line 237 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Trans >
ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::LegacyPose2D ( const Angle< Float > &  angle,
const ecl::linear_algebra::MatrixBase< Trans > &  T 
)
inline

Construct the pose using a rotational angle and a translation vector.

This accepts an angle (or its Float equivalent) and an arbitrary eigen type to use as a translation vector.

Parameters
angle: initial heading angle (double is compatible)(radians).
T: 2x1 translation vector (will compile error if incorrect size).
Template Parameters
Trans: any compatible eigen 2x1 matrix type (e.g. Matrix<Float,2,1>).

Definition at line 252 of file legacy_pose2d.hpp.

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

Copy constructor that works for copies from any pose type.

This works regardless of whatever storage the incoming pose is in.

Parameters
pose: the pose to copy.

Definition at line 264 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
virtual ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::~LegacyPose2D ( )
inlinevirtual

Definition at line 269 of file legacy_pose2d.hpp.

Member Function Documentation

template<typename Float , enum Pose2DStorageType Storage>
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::heading ( const Angle< Float > &  value)
inline

Sets the heading.

Definition at line 359 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Angle<Float> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::heading ( ) const
inline

Get the heading.

Definition at line 388 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
static LegacyPose2D<Float,Storage> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::Identity ( )
inlinestatic

Static function for returning the idenitity pose, eigen style.

Returns
Pose2D<Float,Storage> : the zero rotation, zero translation pose.

Definition at line 349 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
LegacyPose2D<Float,Storage> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::inverse ( ) const
inline

Calculate the inverse pose.

This calculates the reverse transformation between frames.

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

Definition at line 401 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
LegacyPose2D<Float,Storage> ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::operator* ( const LegacyPose2D< Float, Storage_ > &  pose) const
inline

Combine this pose with the incoming pose.

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

Definition at line 414 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
LegacyPose2D<Float>& ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::operator*= ( const LegacyPose2D< Float > &  pose)
inline

Transform this pose by the specified input pose.

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

Definition at line 422 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
LegacyPose2D<Float,Storage>& ecl::LegacyPose2D< Float, Storage, 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 280 of file legacy_pose2d.hpp.

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

Relative pose between this pose and another.

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

Pose2D<double> a(1.0,1.0,1.57), b(1.0,2.0,3.14);
Pose2D<double> brela = b.relative(a);
std::cout << brela << std::endl; // [1.0, 0.0, 1.57]
Parameters
pose: reference frame for the relative pose.
Returns
Pose2D<Float> : new instance representing the relative.

Definition at line 442 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::rotation ( const Angle< Float > &  heading)
inline

Set the rotational component with a heading angle.

This accepts an input heading angle to configure the internal rotational storage.

Parameters
heading: configure the rotation from an input heading angle.

Definition at line 297 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::rotation ( const RotationMatrix rotation_matrix)
inline

Set the rotational component with a rotation matrix.

This accepts an input rotation matrix to configure the internal rotational storage.

Parameters
rotation_matrix: input to copy across to the internal rotational storage.

Definition at line 308 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
RotationType& ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::rotation ( )
inline

Definition at line 378 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
const RotationType& ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::rotation ( ) const
inline

Return a mutable handle to the translation vector.

>

Definition at line 380 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Rot >
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::rotationMatrix ( const ecl::linear_algebra::MatrixBase< Rot > &  rotation_matrix)
inline

Set the rotational component.

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

Parameters
rotation_matrix: 2x2 rotation matrix.
Template Parameters
Rot: any compatible eigen 2x2 matrix type (e.g. Matrix<Float,2,2>).

Definition at line 371 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
RotationMatrix ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::rotationMatrix ( ) const
inline

Representation of the rotation in matrix form.

Definition at line 389 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::setIdentity ( )
inline

Set this pose to zero rotation and zero translation.

Definition at line 339 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::setPose ( const Float &  x,
const Float &  y,
const Angle< Float > &  heading 
)
inline

Sets the pose with a triplet.

Definition at line 356 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::translation ( const Float &  x,
const Float &  y 
)
inline

Set the translation vector from a pair of x,y values.

This accepts x, y values to set the pose translation.

Parameters
x: x translation.
y: y translation.

Definition at line 319 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Trans >
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::translation ( const ecl::linear_algebra::MatrixBase< Trans > &  T)
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
T: 2x1 translation vector.
Template Parameters
Trans: any compatible eigen 2x1 matrix type (e.g. Matrix<Float,2,1>).

Definition at line 332 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Translation& ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::translation ( )
inline

Return a mutable handle to the rotational storage component.

>

Definition at line 379 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
const Translation& ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::translation ( ) const
inline

Return a const handle to the rotational storage component.

>

Definition at line 381 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::x ( const Float &  value)
inline

Sets the x-coordinate.

Definition at line 357 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Float ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::x ( ) const
inline

Return a const handle to the translation vector.

>Get the x-coordinate.

Definition at line 386 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::y ( const Float &  value)
inline

Sets the y-coordinate.

Definition at line 358 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Float ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::y ( ) const
inline

Get the y-coordinate.

Definition at line 387 of file legacy_pose2d.hpp.

Friends And Related Function Documentation

template<typename Float , enum Pose2DStorageType Storage>
template<typename OutputStream , typename Float_ , enum Pose2DStorageType Storage_>
OutputStream& operator<< ( OutputStream &  ostream,
const LegacyPose2D< Float_, Storage_ > &  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 475 of file legacy_pose2d.hpp.

Member Data Documentation

template<typename Float , enum Pose2DStorageType Storage>
RotationType ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::rot
private

Definition at line 453 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Float ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::Scalar

Eigen style declaration of the element type.

Definition at line 193 of file legacy_pose2d.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Translation ecl::LegacyPose2D< Float, Storage, enable_if< is_float< Float > >::type >::trans
private

Definition at line 454 of file legacy_pose2d.hpp.


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


ecl_geometry
Author(s): Daniel Stonier
autogenerated on Mon Jun 10 2019 13:08:38