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 geometry_msgs::Quaternion &q) |
tf2::Quaternion | toQuaternion (const geometry_msgs::QuaternionStamped &q) |
template<typename T > | |
tf2::Quaternion | toQuaternion (const T &t) |
tf2::Quaternion | toQuaternion (const tf2::Quaternion &q) |
template<typename T > | |
tf2::Quaternion | toQuaternion (const tf2::Stamped< T > &t) |
|
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);
q | a tf2::Quaternion |
yaw | the computed yaw |
pitch | the computed pitch |
roll | the computed roll |
Definition at line 87 of file impl/utils.h.
|
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
q | a tf2::Quaternion |
Definition at line 123 of file impl/utils.h.
|
inline |
Function needed for the generalization of toQuaternion
q | a geometry_msgs::Quaternion |
Definition at line 39 of file impl/utils.h.
|
inline |
Function needed for the generalization of toQuaternion
q | a geometry_msgs::QuaternionStamped |
Definition at line 50 of file impl/utils.h.
tf2::Quaternion tf2::impl::toQuaternion | ( | const T & | t | ) |
Generic version of toQuaternion. It tries to convert the argument to a geometry_msgs::Quaternion
t | some object |
Definition at line 72 of file impl/utils.h.
|
inline |
Function needed for the generalization of toQuaternion
q | a tf2::Quaternion |
Definition at line 30 of file impl/utils.h.
tf2::Quaternion tf2::impl::toQuaternion | ( | const tf2::Stamped< T > & | t | ) |
Function needed for the generalization of toQuaternion
t | some tf2::Stamped object |
Definition at line 61 of file impl/utils.h.