se2ez
se2ez::tf Namespace Reference

Helper functions for transform manipulation. More...

Typedefs

template<typename V >
using EigenVector = std::vector< V, Eigen::aligned_allocator< V > >
 A template for a vector that stores Eigen objects. More...
 
template<typename K , typename V >
using EigenMap = std::map< K, V, std::less< K >, Eigen::aligned_allocator< std::pair< const K, V > >>
 A template for a map that stores Eigen objects. More...
 
template<typename K , typename V >
using EigenHash = std::unordered_map< K, V, std::hash< K >, std::equal_to< K >, Eigen::aligned_allocator< std::pair< const K, V > >>
 A template for an unordered map that stores Eigen objects. More...
 

Functions

Eigen Isometry2d operations
Eigen::Isometry2d toIsometry (double x, double y, double theta)
 Converts a translation (x, y) and rotation from X-axis (theta) into a transform. More...
 
double getRotation (const Eigen::Isometry2d &frame)
 Gets rotation from a frame from the X-axis (t) More...
 
Eigen::Isometry2d toIsometry (const Eigen::Vector3d &vec)
 Converts a vector [x, y, t] composed of a translation (x, y) and rotation from X-axis (t) into a transform. More...
 
double transformDistance (const Eigen::Isometry2d &t1, const Eigen::Isometry2d &t2=Eigen::Isometry2d::Identity(), double alpha=0.75)
 Return the transform distance between two transformations, w is the weight of the euclidean distance, and (1-w) the weight of the rotational distance (wrapping from -pi to pi). More...
 
Eigen::Vector3d flattenIsometry (const Eigen::Isometry2d &frame)
 Converts a transformation frame into a vector [x, y, t] composed of a translation (x, y) and rotation from X-axis(t). More...
 
KDL and Eigen Conversions
KDL::Frame EigenToKDLFrame (const Eigen::Isometry2d &iso)
 Converts an Eigen transformation into a KDL transformation. More...
 
Eigen::Isometry2d KDLToEigenFrame (const KDL::Frame &frame)
 Converts an KDL transformation into a Eigen transformation. More...
 
KDL::JntArray EigenToKDLVec (const Eigen::VectorXd &vec)
 Converts an Eigen vector into a KDL vector. More...
 
Eigen::VectorXd KDLToEigenVec (const KDL::JntArray &array)
 Converts an KDL vector into a Eigen vector. More...
 
Debug & Output
std::string printFrame (const Eigen::Isometry2d &frame)
 Returns a string "[x, y, t]" of the translation (x, y) and rotation (t) component of a transform. More...
 
std::string printFrame (const KDL::Frame &frame)
 Returns a string "[x, y, t]" of the translation (x, y) and rotation (t) component of a transform. More...
 
std::string printVector (const Eigen::VectorXd &v, unsigned int precision=4)
 Returns a string of a vector's contents. More...
 
std::string printMatrix (const Eigen::MatrixXd &v, unsigned int precision=4)
 Returns a string of a matrix's contents. More...
 

Detailed Description

Helper functions for transform manipulation.

Typedef Documentation

◆ EigenHash

template<typename K , typename V >
using se2ez::tf::EigenHash = typedef std::unordered_map<K, V, std::hash<K>, std::equal_to<K>, Eigen::aligned_allocator<std::pair<const K, V> >>

A template for an unordered map that stores Eigen objects.

Template Parameters
KKey for the map (not an Eigen type).
VValue for the map (contains an Eigen type).

Definition at line 149 of file math.h.

◆ EigenMap

template<typename K , typename V >
using se2ez::tf::EigenMap = typedef std::map<K, V, std::less<K>, Eigen::aligned_allocator<std::pair<const K, V> >>

A template for a map that stores Eigen objects.

Template Parameters
KKey for the map (not an Eigen type).
VValue for the map (contains an Eigen type).

Definition at line 140 of file math.h.

◆ EigenVector

template<typename V >
using se2ez::tf::EigenVector = typedef std::vector<V, Eigen::aligned_allocator<V> >

A template for a vector that stores Eigen objects.

Template Parameters
VValue for the vector (contains an Eigen type).

Definition at line 131 of file math.h.

Function Documentation

◆ EigenToKDLFrame()

KDL::Frame se2ez::tf::EigenToKDLFrame ( const Eigen::Isometry2d &  iso)

Converts an Eigen transformation into a KDL transformation.

Parameters
[in]isoEigen transform.
Returns
KDL transform.

Definition at line 48 of file math.cpp.

◆ EigenToKDLVec()

KDL::JntArray se2ez::tf::EigenToKDLVec ( const Eigen::VectorXd &  vec)

Converts an Eigen vector into a KDL vector.

Parameters
[in]vecEigen vector.
Returns
KDL vector.

Definition at line 66 of file math.cpp.

◆ flattenIsometry()

Eigen::Vector3d se2ez::tf::flattenIsometry ( const Eigen::Isometry2d &  frame)

Converts a transformation frame into a vector [x, y, t] composed of a translation (x, y) and rotation from X-axis(t).

Parameters
[in]frameTransform to flatten.
Returns
Vector representation of transform.

Definition at line 30 of file math.cpp.

◆ getRotation()

double se2ez::tf::getRotation ( const Eigen::Isometry2d &  frame)

Gets rotation from a frame from the X-axis (t)

Parameters
[in]frameFrame to get rotation from.
Returns
Angle of transformation.

Definition at line 25 of file math.cpp.

◆ KDLToEigenFrame()

Eigen::Isometry2d se2ez::tf::KDLToEigenFrame ( const KDL::Frame &  frame)

Converts an KDL transformation into a Eigen transformation.

Parameters
[in]frameKDL transform.
Returns
Eigen transform.

Definition at line 55 of file math.cpp.

◆ KDLToEigenVec()

Eigen::VectorXd se2ez::tf::KDLToEigenVec ( const KDL::JntArray &  array)

Converts an KDL vector into a Eigen vector.

Parameters
[in]arrayKDL vector.
Returns
Eigen vector.

Definition at line 74 of file math.cpp.

◆ printFrame() [1/2]

std::string se2ez::tf::printFrame ( const Eigen::Isometry2d &  frame)

Returns a string "[x, y, t]" of the translation (x, y) and rotation (t) component of a transform.

Parameters
[in]frameFrame to print.
Returns
Printable string of transform data.

Definition at line 79 of file math.cpp.

◆ printFrame() [2/2]

std::string se2ez::tf::printFrame ( const KDL::Frame &  frame)

Returns a string "[x, y, t]" of the translation (x, y) and rotation (t) component of a transform.

Parameters
[in]frameFrame to print.
Returns
Printable string of transform data.

Definition at line 85 of file math.cpp.

◆ printMatrix()

std::string se2ez::tf::printMatrix ( const Eigen::MatrixXd &  v,
unsigned int  precision = 4 
)

Returns a string of a matrix's contents.

Parameters
[in]vMatrix to print.
[in]precisionPrecision to print floating point values at.
Returns
Printable string of vector.

Definition at line 109 of file math.cpp.

◆ printVector()

std::string se2ez::tf::printVector ( const Eigen::VectorXd &  v,
unsigned int  precision = 4 
)

Returns a string of a vector's contents.

Parameters
[in]vVector to print.
[in]precisionPrecision to print floating point values at.
Returns
Printable string of vector.

Definition at line 90 of file math.cpp.

◆ toIsometry() [1/2]

Eigen::Isometry2d se2ez::tf::toIsometry ( double  x,
double  y,
double  theta 
)

Converts a translation (x, y) and rotation from X-axis (theta) into a transform.

Parameters
[in]xX coordinate of translation.
[in]yY coordinate of translation.
[in]thetaRotation from the X-axis.
Returns
Transform corresponding to input.

Definition at line 11 of file math.cpp.

◆ toIsometry() [2/2]

Eigen::Isometry2d se2ez::tf::toIsometry ( const Eigen::Vector3d &  vec)

Converts a vector [x, y, t] composed of a translation (x, y) and rotation from X-axis (t) into a transform.

Parameters
[in]vecVector representation of transform.
Returns
Transform corresponding to input.

Definition at line 20 of file math.cpp.

◆ transformDistance()

double se2ez::tf::transformDistance ( const Eigen::Isometry2d &  t1,
const Eigen::Isometry2d &  t2 = Eigen::Isometry2d::Identity(),
double  alpha = 0.75 
)

Return the transform distance between two transformations, w is the weight of the euclidean distance, and (1-w) the weight of the rotational distance (wrapping from -pi to pi).

Parameters
[in]t1First transform.
[in]t2Second transform.
[in]alphaWeight of the euclidean distance (must be between 0 and 1).
Returns
The weighted distance between the transforms.

Definition at line 36 of file math.cpp.