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

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

#include <pose2d_eigen2.hpp>

List of all members.

Public Types

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

Public Member Functions

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

Static Public Member Functions

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

Public Attributes

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

Private Attributes

RotationType rot
Translation trans

Friends

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

Detailed Description

template<typename Float, enum Pose2DStorageType Storage>
class ecl::Pose2D< 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:

 Pose2D<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 167 of file pose2d_eigen2.hpp.


Member Typedef Documentation

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

Rotational math specific to rotational angles.

Definition at line 180 of file pose2d_eigen2.hpp.

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

Rotational math specific to rotational angles.

Definition at line 181 of file pose2d_eigen3.hpp.

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

Rotational math specific to this storage type.

Definition at line 178 of file pose2d_eigen2.hpp.

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

Rotational math specific to this storage type.

Definition at line 179 of file pose2d_eigen3.hpp.

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

The type used to represent rotation matrices.

Definition at line 182 of file pose2d_eigen2.hpp.

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

The type used to represent rotation matrices.

Definition at line 183 of file pose2d_eigen3.hpp.

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

Rotational math specific to rotational matrices.

Definition at line 179 of file pose2d_eigen2.hpp.

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

Rotational math specific to rotational matrices.

Definition at line 180 of file pose2d_eigen3.hpp.

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

The type used for storage of the rotation/angle.

Definition at line 181 of file pose2d_eigen2.hpp.

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

The type used for storage of the rotation/angle.

Definition at line 182 of file pose2d_eigen3.hpp.

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

The type used to represent translations.

Definition at line 183 of file pose2d_eigen2.hpp.

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

The type used to represent translations.

Definition at line 184 of file pose2d_eigen3.hpp.


Constructor & Destructor Documentation

template<typename Float , enum Pose2DStorageType Storage>
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( ) [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 196 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( 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 204 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Rot , typename Trans >
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( 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 221 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Trans >
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( 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 236 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( const Pose2D< 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 248 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
virtual ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::~Pose2D ( ) [inline, virtual]

Definition at line 253 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( ) [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 197 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( 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 205 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Rot , typename Trans >
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( 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 222 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Trans >
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( 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 237 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Pose2D ( const Pose2D< 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 249 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
virtual ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::~Pose2D ( ) [inline, virtual]

Definition at line 254 of file pose2d_eigen3.hpp.


Member Function Documentation

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

Sets the heading.

Definition at line 344 of file pose2d_eigen2.hpp.

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

Sets the heading.

Definition at line 344 of file pose2d_eigen3.hpp.

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

Get the heading.

Definition at line 373 of file pose2d_eigen2.hpp.

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

Get the heading.

Definition at line 373 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
static Pose2D<Float,Storage> ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Identity ( ) [inline, static]

Static function for returning the idenitity pose, eigen style.

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

Definition at line 333 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
static Pose2D<Float,Storage> ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::Identity ( ) [inline, static]

Static function for returning the idenitity pose, eigen style.

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

Definition at line 334 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Pose2D<Float,Storage> ecl::Pose2D< 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 386 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Pose2D<Float,Storage> ecl::Pose2D< 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 386 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
Pose2D<Float,Storage> ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::operator* ( const Pose2D< 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 399 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
Pose2D<Float,Storage> ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::operator* ( const Pose2D< 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 399 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Pose2D<Float>& ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::operator*= ( const Pose2D< 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 407 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Pose2D<Float>& ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::operator*= ( const Pose2D< 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 407 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
Pose2D<Float,Storage>& ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::operator= ( const Pose2D< 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 264 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
Pose2D<Float,Storage>& ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::operator= ( const Pose2D< 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 265 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
Pose2D<Float,Storage> ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::relative ( const Pose2D< 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 427 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<enum Pose2DStorageType Storage_>
Pose2D<Float,Storage> ecl::Pose2D< Float, Storage, enable_if< is_float< Float > >::type >::relative ( const Pose2D< 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 427 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::Pose2D< 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 281 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::Pose2D< 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 282 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::Pose2D< 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 292 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::Pose2D< 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 293 of file pose2d_eigen3.hpp.

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

Definition at line 363 of file pose2d_eigen3.hpp.

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

Definition at line 363 of file pose2d_eigen2.hpp.

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

Return a mutable handle to the translation vector.

>

Definition at line 365 of file pose2d_eigen3.hpp.

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

Return a mutable handle to the translation vector.

>

Definition at line 365 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Rot >
void ecl::Pose2D< 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 356 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Rot >
void ecl::Pose2D< 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 356 of file pose2d_eigen2.hpp.

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

Representation of the rotation in matrix form.

Definition at line 374 of file pose2d_eigen3.hpp.

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

Definition at line 374 of file pose2d_eigen2.hpp.

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

Set this pose to zero rotation and zero translation.

Definition at line 323 of file pose2d_eigen2.hpp.

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

Set this pose to zero rotation and zero translation.

Definition at line 324 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::Pose2D< 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 341 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::Pose2D< 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 341 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::Pose2D< 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 303 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
void ecl::Pose2D< 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 304 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Trans >
void ecl::Pose2D< 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 316 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
template<typename Trans >
void ecl::Pose2D< 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 317 of file pose2d_eigen3.hpp.

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

Return a mutable handle to the rotational storage component.

>

Definition at line 364 of file pose2d_eigen3.hpp.

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

Return a mutable handle to the rotational storage component.

>

Definition at line 364 of file pose2d_eigen2.hpp.

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

Return a const handle to the rotational storage component.

>

Definition at line 366 of file pose2d_eigen3.hpp.

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

Return a const handle to the rotational storage component.

>

Definition at line 366 of file pose2d_eigen2.hpp.

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

Sets the x-coordinate.

Definition at line 342 of file pose2d_eigen2.hpp.

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

Sets the x-coordinate.

Definition at line 342 of file pose2d_eigen3.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Float ecl::Pose2D< 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 371 of file pose2d_eigen2.hpp.

template<typename Float , enum Pose2DStorageType Storage>
Float ecl::Pose2D< 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 371 of file pose2d_eigen3.hpp.

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

Sets the y-coordinate.

Definition at line 343 of file pose2d_eigen3.hpp.

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

Sets the y-coordinate.

Definition at line 343 of file pose2d_eigen2.hpp.

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

Get the y-coordinate.

Definition at line 372 of file pose2d_eigen2.hpp.

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

Get the y-coordinate.

Definition at line 372 of file pose2d_eigen3.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 Pose2D< 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 455 of file pose2d_eigen2.hpp.

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


Member Data Documentation

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

Definition at line 438 of file pose2d_eigen2.hpp.

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

Eigen style declaration of the element type.

Definition at line 177 of file pose2d_eigen2.hpp.

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

Definition at line 439 of file pose2d_eigen2.hpp.


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


ecl_geometry
Author(s): Daniel Stonier
autogenerated on Sun Oct 5 2014 23:36:08