tf2_kdl
master
KDL binding for tf2
|
#include <tf2/convert.h>
#include <tf2_ros/buffer_interface.h>
#include <kdl/frames.hpp>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <geometry_msgs/msg/wrench_stamped.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <builtin_interfaces/msg/time.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>
Go to the source code of this file.
Namespaces | |
tf2 | |
Functions | |
KDL::Frame | tf2::transformToKDL (const geometry_msgs::msg::TransformStamped &t) |
Convert a timestamped transform to the equivalent KDL data type. More... | |
geometry_msgs::msg::TransformStamped | tf2::kdlToTransform (const KDL::Frame &k) |
Convert an KDL Frame to the equivalent geometry_msgs message type. More... | |
template<> | |
void | tf2::doTransform (const tf2::Stamped< KDL::Vector > &t_in, tf2::Stamped< KDL::Vector > &t_out, const geometry_msgs::msg::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. More... | |
geometry_msgs::msg::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. More... | |
void | tf2::fromMsg (const geometry_msgs::msg::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. More... | |
template<> | |
void | tf2::doTransform (const tf2::Stamped< KDL::Twist > &t_in, tf2::Stamped< KDL::Twist > &t_out, const geometry_msgs::msg::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. More... | |
geometry_msgs::msg::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. More... | |
void | tf2::fromMsg (const geometry_msgs::msg::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. More... | |
template<> | |
void | tf2::doTransform (const tf2::Stamped< KDL::Wrench > &t_in, tf2::Stamped< KDL::Wrench > &t_out, const geometry_msgs::msg::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. More... | |
geometry_msgs::msg::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. More... | |
void | tf2::fromMsg (const geometry_msgs::msg::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. More... | |
template<> | |
void | tf2::doTransform (const tf2::Stamped< KDL::Frame > &t_in, tf2::Stamped< KDL::Frame > &t_out, const geometry_msgs::msg::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. More... | |
geometry_msgs::msg::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. More... | |
void | tf2::fromMsg (const geometry_msgs::msg::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. More... | |
geometry_msgs::msg::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. More... | |
void | tf2::fromMsg (const geometry_msgs::msg::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. More... | |