Functions | |
template<> | |
void | doTransform (const geometry_msgs::PoseStamped &t_in, geometry_msgs::PoseStamped &t_out, const geometry_msgs::TransformStamped &transform) |
template<> | |
void | doTransform (const geometry_msgs::PointStamped &t_in, geometry_msgs::PointStamped &t_out, const geometry_msgs::TransformStamped &transform) |
template<> | |
void | doTransform (const geometry_msgs::Vector3Stamped &t_in, geometry_msgs::Vector3Stamped &t_out, const geometry_msgs::TransformStamped &transform) |
void | fromMsg (const geometry_msgs::PoseStamped &msg, geometry_msgs::PoseStamped &out) |
void | fromMsg (const geometry_msgs::PointStamped &msg, geometry_msgs::PointStamped &out) |
void | fromMsg (const geometry_msgs::Vector3Stamped &msg, geometry_msgs::Vector3Stamped &out) |
template<> | |
const std::string & | getFrameId (const geometry_msgs::PoseStamped &t) |
template<> | |
const std::string & | getFrameId (const geometry_msgs::PointStamped &t) |
template<> | |
const std::string & | getFrameId (const geometry_msgs::Vector3Stamped &t) |
template<> | |
const ros::Time & | getTimestamp (const geometry_msgs::PoseStamped &t) |
template<> | |
const ros::Time & | getTimestamp (const geometry_msgs::PointStamped &t) |
template<> | |
const ros::Time & | getTimestamp (const geometry_msgs::Vector3Stamped &t) |
KDL::Frame | gmTransformToKDL (const geometry_msgs::TransformStamped &t) |
geometry_msgs::PoseStamped | toMsg (const geometry_msgs::PoseStamped &in) |
geometry_msgs::PointStamped | toMsg (const geometry_msgs::PointStamped &in) |
geometry_msgs::Vector3Stamped | toMsg (const geometry_msgs::Vector3Stamped &in) |
void tf2::doTransform | ( | const geometry_msgs::PoseStamped & | t_in, | |
geometry_msgs::PoseStamped & | t_out, | |||
const geometry_msgs::TransformStamped & | transform | |||
) | [inline] |
Definition at line 133 of file tf2_geometry_msgs.h.
void tf2::doTransform | ( | const geometry_msgs::PointStamped & | t_in, | |
geometry_msgs::PointStamped & | t_out, | |||
const geometry_msgs::TransformStamped & | transform | |||
) | [inline] |
Definition at line 99 of file tf2_geometry_msgs.h.
void tf2::doTransform | ( | const geometry_msgs::Vector3Stamped & | t_in, | |
geometry_msgs::Vector3Stamped & | t_out, | |||
const geometry_msgs::TransformStamped & | transform | |||
) | [inline] |
Definition at line 64 of file tf2_geometry_msgs.h.
void tf2::fromMsg | ( | const geometry_msgs::PoseStamped & | msg, | |
geometry_msgs::PoseStamped & | out | |||
) |
Definition at line 151 of file tf2_geometry_msgs.h.
void tf2::fromMsg | ( | const geometry_msgs::PointStamped & | msg, | |
geometry_msgs::PointStamped & | out | |||
) |
Definition at line 113 of file tf2_geometry_msgs.h.
void tf2::fromMsg | ( | const geometry_msgs::Vector3Stamped & | msg, | |
geometry_msgs::Vector3Stamped & | out | |||
) |
Definition at line 78 of file tf2_geometry_msgs.h.
const std::string& tf2::getFrameId | ( | const geometry_msgs::PoseStamped & | t | ) | [inline] |
Definition at line 129 of file tf2_geometry_msgs.h.
const std::string& tf2::getFrameId | ( | const geometry_msgs::PointStamped & | t | ) | [inline] |
Definition at line 95 of file tf2_geometry_msgs.h.
const std::string& tf2::getFrameId | ( | const geometry_msgs::Vector3Stamped & | t | ) | [inline] |
Definition at line 60 of file tf2_geometry_msgs.h.
const ros::Time& tf2::getTimestamp | ( | const geometry_msgs::PoseStamped & | t | ) | [inline] |
PoseStamped
Definition at line 125 of file tf2_geometry_msgs.h.
const ros::Time& tf2::getTimestamp | ( | const geometry_msgs::PointStamped & | t | ) | [inline] |
PointStamped
Definition at line 91 of file tf2_geometry_msgs.h.
const ros::Time& tf2::getTimestamp | ( | const geometry_msgs::Vector3Stamped & | t | ) | [inline] |
Vector3Stamped
Definition at line 56 of file tf2_geometry_msgs.h.
KDL::Frame tf2::gmTransformToKDL | ( | const geometry_msgs::TransformStamped & | t | ) |
Definition at line 42 of file tf2_geometry_msgs.h.
geometry_msgs::PoseStamped tf2::toMsg | ( | const geometry_msgs::PoseStamped & | in | ) |
Definition at line 147 of file tf2_geometry_msgs.h.
geometry_msgs::PointStamped tf2::toMsg | ( | const geometry_msgs::PointStamped & | in | ) |
Definition at line 109 of file tf2_geometry_msgs.h.
geometry_msgs::Vector3Stamped tf2::toMsg | ( | const geometry_msgs::Vector3Stamped & | in | ) |
Definition at line 74 of file tf2_geometry_msgs.h.