tf2 rolling
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
Loading...
Searching...
No Matches
tf2::impl Namespace Reference

Classes

class  Converter

Functions

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

Function Documentation

◆ toQuaternion() [1/5]

tf2::Quaternion tf2::impl::toQuaternion ( const tf2::Quaternion & q)
inline

Function needed for the generalization of toQuaternion

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

◆ toQuaternion() [2/5]

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

Function needed for the generalization of toQuaternion

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

◆ toQuaternion() [3/5]

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

Function needed for the generalization of toQuaternion

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

◆ toQuaternion() [4/5]

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

◆ toQuaternion() [5/5]

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::msg::Quaternion

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

◆ getEulerYPR()

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

◆ getYaw()

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