OpenWalker Project
Documentation of the ROS Packages
Public Types | Public Member Functions | Static Public Member Functions | List of all members
ow_core::CartesianPosition< _Scalar > Class Template Reference

The CartesianPosition class. More...

#include <cartesian_position.h>

Inheritance diagram for ow_core::CartesianPosition< _Scalar >:

Public Types

typedef _Scalar Scalar
 
typedef Eigen::Matrix< Scalar, 7, 1 > Base
 
typedef Eigen::Transform< Scalar, 3, Eigen::Affine > Transform
 

Public Member Functions

 CartesianPosition ()
 Default Constructor.
 
template<typename OtherDerived >
 CartesianPosition (const Eigen::EigenBase< OtherDerived > &other)
 Copy constructor. More...
 
 CartesianPosition (const Transform &other)
 Copy constructor from Eigen::Transform. More...
 
 CartesianPosition (const Scalar &x, const Scalar &y, const Scalar &z, const Scalar &qw, const Scalar &qx, const Scalar &qy, const Scalar &qz)
 Constructor from Scalars.
 
 CartesianPosition (const typename Transform::TranslationType &other)
 Copy constructor from Eigen::Translation. More...
 
template<typename OtherDerived >
 CartesianPosition (const Eigen::RotationBase< OtherDerived, 3 > &other)
 Copy constructor from Eigen::RotationBase. More...
 
 CartesianPosition (const tf::Transform &other)
 Copy constructor from tf::Transform.
 
 CartesianPosition (const geometry_msgs::Pose &other)
 Copy constructor from geometry_msgs::Pose.
 
void setIdentity ()
 set to identity.
 
void operator= (const Transform &T)
 Assignment form Eigen::Transformation.
 
void operator= (const tf::Transform &T)
 Assignment form tf::Transform.
 
void operator= (const geometry_msgs::Pose &T)
 Assignment form geometry_msgs::Pose.
 
template<typename OtherDerived >
void operator= (const Eigen::RotationBase< OtherDerived, 3 > &R)
 Assignment form Eigen::RotationBase.
 
void operator= (const typename Transform::TranslationType &t)
 Assignment form Eigen::Translation.
 
 operator Transform () const
 Conversion to Eigen::Transformation.
 
 operator tf::Transform () const
 Conversion to tf::Transform.
 
 operator geometry_msgs::Pose () const
 Conversion to geometry_msgs::Pose.
 
Transform toTransformEigen ()
 Conversion to Eigen::Transformation.
 
tf::Transform toTransformTf ()
 Conversion to tf::Transform.
 
geometry_msgs::Pose toPoseMsg ()
 Conversion to geometry_msgs::Pose.
 
LinearPositionRef< Base > position ()
 access to position part
 
LinearPositionRef< const Base > position () const
 const access to position part
 
AngularPositionRef< Base > orientation ()
 access to orientation part
 
AngularPositionRef< const Base > orientation () const
 const access to orientation part
 
std::string toString () const
 Conversion to std::string.
 

Static Public Member Functions

static const CartesianPositionIdentity ()
 Construct as Identity. More...
 
static const CartesianPositionDefault ()
 Construct as Default. More...
 

Detailed Description

template<typename _Scalar>
class ow_core::CartesianPosition< _Scalar >

The CartesianPosition class.

The CartesianPosition is of type Eigen::Vector7 and is represented by the math symbol $\mathbf{X}$.

Stores the position and orientation information in a 7 dimensional vector. The position part is represented by the first three elements. The orientation as a quaternion by the last four elements.

Constructor & Destructor Documentation

template<typename _Scalar >
template<typename OtherDerived >
ow_core::CartesianPosition< _Scalar >::CartesianPosition ( const Eigen::EigenBase< OtherDerived > &  other)
inline

Copy constructor.

This copy constructor not only works with Eigen matrices but also with their expressions.

template<typename _Scalar >
ow_core::CartesianPosition< _Scalar >::CartesianPosition ( const Transform &  other)
inline

Copy constructor from Eigen::Transform.

Todo:
: removed explicit to write things like: CartesianPosition X = Eigen::Affine3d::Identity();
template<typename _Scalar >
ow_core::CartesianPosition< _Scalar >::CartesianPosition ( const typename Transform::TranslationType &  other)
inlineexplicit

Copy constructor from Eigen::Translation.

This Constructor sets the rotational part to identity.

template<typename _Scalar >
template<typename OtherDerived >
ow_core::CartesianPosition< _Scalar >::CartesianPosition ( const Eigen::RotationBase< OtherDerived, 3 > &  other)
inlineexplicit

Copy constructor from Eigen::RotationBase.

This Constructor sets the translational part to zero.

Member Function Documentation

template<typename _Scalar >
static const CartesianPosition& ow_core::CartesianPosition< _Scalar >::Default ( )
inlinestatic

Construct as Default.

Default is Identity

template<typename _Scalar >
static const CartesianPosition& ow_core::CartesianPosition< _Scalar >::Identity ( )
inlinestatic

Construct as Identity.

Todo:
maby expression

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