#include <tf2/convert.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <kdl/frames.hpp>
Go to the source code of this file.
Namespaces | |
namespace | tf2 |
Functions | |
template<> | |
void | tf2::doTransform (const geometry_msgs::Vector3Stamped &t_in, geometry_msgs::Vector3Stamped &t_out, const geometry_msgs::TransformStamped &transform) |
template<> | |
void | tf2::doTransform (const geometry_msgs::PointStamped &t_in, geometry_msgs::PointStamped &t_out, const geometry_msgs::TransformStamped &transform) |
template<> | |
void | tf2::doTransform (const geometry_msgs::PoseStamped &t_in, geometry_msgs::PoseStamped &t_out, const geometry_msgs::TransformStamped &transform) |
void | tf2::fromMsg (const geometry_msgs::Vector3Stamped &msg, geometry_msgs::Vector3Stamped &out) |
void | tf2::fromMsg (const geometry_msgs::PointStamped &msg, geometry_msgs::PointStamped &out) |
void | tf2::fromMsg (const geometry_msgs::PoseStamped &msg, geometry_msgs::PoseStamped &out) |
template<> | |
const std::string & | tf2::getFrameId (const geometry_msgs::Vector3Stamped &t) |
template<> | |
const std::string & | tf2::getFrameId (const geometry_msgs::PointStamped &t) |
template<> | |
const std::string & | tf2::getFrameId (const geometry_msgs::PoseStamped &t) |
template<> | |
const ros::Time & | tf2::getTimestamp (const geometry_msgs::Vector3Stamped &t) |
template<> | |
const ros::Time & | tf2::getTimestamp (const geometry_msgs::PointStamped &t) |
template<> | |
const ros::Time & | tf2::getTimestamp (const geometry_msgs::PoseStamped &t) |
KDL::Frame | tf2::gmTransformToKDL (const geometry_msgs::TransformStamped &t) |
geometry_msgs::Vector3Stamped | tf2::toMsg (const geometry_msgs::Vector3Stamped &in) |
geometry_msgs::PointStamped | tf2::toMsg (const geometry_msgs::PointStamped &in) |
geometry_msgs::PoseStamped | tf2::toMsg (const geometry_msgs::PoseStamped &in) |