Classes | Functions
tf2::impl Namespace Reference

Classes

class  Converter

Functions

void getEulerYPR (const tf2::Quaternion &q, double &yaw, double &pitch, double &roll)
double getYaw (const tf2::Quaternion &q)
tf2::Quaternion toQuaternion (const tf2::Quaternion &q)
tf2::Quaternion toQuaternion (const geometry_msgs::Quaternion &q)
tf2::Quaternion toQuaternion (const geometry_msgs::QuaternionStamped &q)
template<typename T >
tf2::Quaternion toQuaternion (const tf2::Stamped< T > &t)
template<typename T >
tf2::Quaternion toQuaternion (const T &t)

Function Documentation

void tf2::impl::getEulerYPR ( const tf2::Quaternion q,
double &  yaw,
double &  pitch,
double &  roll 
) [inline]

The code below is blantantly copied from urdfdom_headers only the normalization has been added. It computes the Euler roll, pitch yaw from a tf2::Quaternion It is equivalent to tf2::Matrix3x3(q).getEulerYPR(yaw, pitch, roll);

Parameters:
qa tf2::Quaternion
yawthe computed yaw
pitchthe computed pitch
rollthe computed roll

Definition at line 87 of file impl/utils.h.

double tf2::impl::getYaw ( const tf2::Quaternion q) [inline]

The code below is a simplified version of getEulerRPY that only returns the yaw. It is mostly useful in navigation where only yaw matters

Parameters:
qa tf2::Quaternion
Returns:
the computed yaw

Definition at line 123 of file impl/utils.h.

Function needed for the generalization of toQuaternion

Parameters:
qa tf2::Quaternion
Returns:
a copy of the same quaternion

Definition at line 30 of file impl/utils.h.

tf2::Quaternion tf2::impl::toQuaternion ( const geometry_msgs::Quaternion &  q) [inline]

Function needed for the generalization of toQuaternion

Parameters:
qa geometry_msgs::Quaternion
Returns:
a copy of the same quaternion as a tf2::Quaternion

Definition at line 39 of file impl/utils.h.

tf2::Quaternion tf2::impl::toQuaternion ( const geometry_msgs::QuaternionStamped &  q) [inline]

Function needed for the generalization of toQuaternion

Parameters:
qa geometry_msgs::QuaternionStamped
Returns:
a copy of the same quaternion as a tf2::Quaternion

Definition at line 50 of file impl/utils.h.

template<typename T >
tf2::Quaternion tf2::impl::toQuaternion ( const tf2::Stamped< T > &  t)

Function needed for the generalization of toQuaternion

Parameters:
tsome tf2::Stamped object
Returns:
a copy of the same quaternion as a tf2::Quaternion

Definition at line 61 of file impl/utils.h.

template<typename T >
tf2::Quaternion tf2::impl::toQuaternion ( const T &  t)

Generic version of toQuaternion. It tries to convert the argument to a geometry_msgs::Quaternion

Parameters:
tsome object
Returns:
a copy of the same quaternion as a tf2::Quaternion

Definition at line 72 of file impl/utils.h.



tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Oct 2 2017 02:24:35