#include <tf2/convert.h>
#include <kdl/frames.hpp>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/TwistStamped.h>
#include <geometry_msgs/WrenchStamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Pose.h>
Go to the source code of this file.
Namespaces | |
namespace | tf2 |
Functions | |
template<> | |
void | tf2::doTransform (const tf2::Stamped< KDL::Vector > &t_in, tf2::Stamped< KDL::Vector > &t_out, const geometry_msgs::TransformStamped &transform) |
Apply a geometry_msgs TransformStamped to an KDL-specific Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. | |
template<> | |
void | tf2::doTransform (const tf2::Stamped< KDL::Twist > &t_in, tf2::Stamped< KDL::Twist > &t_out, const geometry_msgs::TransformStamped &transform) |
Apply a geometry_msgs TransformStamped to an KDL-specific Twist type. This function is a specialization of the doTransform template defined in tf2/convert.h. | |
template<> | |
void | tf2::doTransform (const tf2::Stamped< KDL::Wrench > &t_in, tf2::Stamped< KDL::Wrench > &t_out, const geometry_msgs::TransformStamped &transform) |
Apply a geometry_msgs TransformStamped to an KDL-specific Wrench type. This function is a specialization of the doTransform template defined in tf2/convert.h. | |
template<> | |
void | tf2::doTransform (const tf2::Stamped< KDL::Frame > &t_in, tf2::Stamped< KDL::Frame > &t_out, const geometry_msgs::TransformStamped &transform) |
Apply a geometry_msgs TransformStamped to a KDL-specific Frame data type. This function is a specialization of the doTransform template defined in tf2/convert.h. | |
void | tf2::fromMsg (const geometry_msgs::PointStamped &msg, tf2::Stamped< KDL::Vector > &out) |
Convert a PointStamped message type to a stamped KDL-specific Vector type. This function is a specialization of the fromMsg template defined in tf2/convert.h. | |
void | tf2::fromMsg (const geometry_msgs::TwistStamped &msg, tf2::Stamped< KDL::Twist > &out) |
Convert a TwistStamped message type to a stamped KDL-specific Twist type. This function is a specialization of the fromMsg template defined in tf2/convert.h. | |
void | tf2::fromMsg (const geometry_msgs::WrenchStamped &msg, tf2::Stamped< KDL::Wrench > &out) |
Convert a WrenchStamped message type to a stamped KDL-specific Wrench type. This function is a specialization of the fromMsg template defined in tf2/convert.h. | |
void | tf2::fromMsg (const geometry_msgs::Pose &msg, KDL::Frame &out) |
Convert a Pose message type to a KDL Frame. This function is a specialization of the fromMsg template defined in tf2/convert.h. | |
void | tf2::fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< KDL::Frame > &out) |
Convert a Pose message transform type to a stamped KDL Frame. This function is a specialization of the fromMsg template defined in tf2/convert.h. | |
geometry_msgs::TransformStamped | tf2::kdlToTransform (const KDL::Frame &k) |
Convert an KDL Frame to the equivalent geometry_msgs message type. | |
geometry_msgs::PointStamped | tf2::toMsg (const tf2::Stamped< KDL::Vector > &in) |
Convert a stamped KDL Vector type to a PointStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. | |
geometry_msgs::TwistStamped | tf2::toMsg (const tf2::Stamped< KDL::Twist > &in) |
Convert a stamped KDL Twist type to a TwistStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. | |
geometry_msgs::WrenchStamped | tf2::toMsg (const tf2::Stamped< KDL::Wrench > &in) |
Convert a stamped KDL Wrench type to a WrenchStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. | |
geometry_msgs::Pose | tf2::toMsg (const KDL::Frame &in) |
Convert a stamped KDL Frame type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. | |
geometry_msgs::PoseStamped | tf2::toMsg (const tf2::Stamped< KDL::Frame > &in) |
Convert a stamped KDL Frame type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. | |
KDL::Frame | tf2::transformToKDL (const geometry_msgs::TransformStamped &t) |
Convert a timestamped transform to the equivalent KDL data type. |