Functions | |
template<> | |
void | doTransform (const tf2::Stamped< btTransform > &t_in, tf2::Stamped< btTransform > &t_out, const geometry_msgs::TransformStamped &transform) |
template<> | |
void | doTransform (const tf2::Stamped< btVector3 > &t_in, tf2::Stamped< btVector3 > &t_out, const geometry_msgs::TransformStamped &transform) |
void | fromMsg (const geometry_msgs::PointStamped &msg, tf2::Stamped< btVector3 > &out) |
geometry_msgs::PointStamped | toMsg (const tf2::Stamped< btVector3 > &in) |
btTransform | transformToBullet (const geometry_msgs::TransformStamped &t) |
void tf2::doTransform | ( | const tf2::Stamped< btTransform > & | t_in, | |
tf2::Stamped< btTransform > & | t_out, | |||
const geometry_msgs::TransformStamped & | transform | |||
) | [inline] |
Definition at line 79 of file tf2_bullet.h.
void tf2::doTransform | ( | const tf2::Stamped< btVector3 > & | t_in, | |
tf2::Stamped< btVector3 > & | t_out, | |||
const geometry_msgs::TransformStamped & | transform | |||
) | [inline] |
Definition at line 50 of file tf2_bullet.h.
void tf2::fromMsg | ( | const geometry_msgs::PointStamped & | msg, | |
tf2::Stamped< btVector3 > & | out | |||
) |
Definition at line 67 of file tf2_bullet.h.
geometry_msgs::PointStamped tf2::toMsg | ( | const tf2::Stamped< btVector3 > & | in | ) |
Definition at line 56 of file tf2_bullet.h.
btTransform tf2::transformToBullet | ( | const geometry_msgs::TransformStamped & | t | ) |
Definition at line 40 of file tf2_bullet.h.