30 #ifndef CONVERSIONS_TF_KDL_H 31 #define CONVERSIONS_TF_KDL_H 35 #include "kdl/frames.hpp" 37 #include <geometry_msgs/Pose.h> 38 #include <geometry_msgs/Twist.h> 71 ROS_DEPRECATED geometry_msgs::Pose
addDelta(
const geometry_msgs::Pose &pose,
const geometry_msgs::Twist &twist,
const double &t);
ROS_DEPRECATED void TransformTFToKDL(const tf::Transform &t, KDL::Frame &k)
Converts a tf Transform into a KDL Frame.
ROS_DEPRECATED void PoseKDLToTF(const KDL::Frame &k, tf::Pose &t)
Converts a KDL Frame into a tf Pose.
ROS_DEPRECATED void PoseTFToKDL(const tf::Pose &t, KDL::Frame &k)
Converts a tf Pose into a KDL Frame.
ROS_DEPRECATED void TransformKDLToTF(const KDL::Frame &k, tf::Transform &t)
Converts a KDL Frame into a tf Transform.
void vectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t)
Converts a tf Vector3 into a KDL Vector.
void transformKDLToTF(const KDL::Frame &k, tf::Transform &t)
Converts a KDL Frame into a tf Transform.
void quaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t)
Converts a tf Quaternion into a KDL Rotation.
void poseTFToKDL(const tf::Pose &t, KDL::Frame &k)
Converts a tf Pose into a KDL Frame.
ROS_DEPRECATED void QuaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k)
Converts a tf Quaternion into a KDL Rotation.
void poseKDLToTF(const KDL::Frame &k, tf::Pose &t)
Converts a KDL Frame into a tf Pose.
void transformTFToKDL(const tf::Transform &t, KDL::Frame &k)
Converts a tf Transform into a KDL Frame.
void vectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k)
Converts a tf Vector3 into a KDL Vector.
void quaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k)
Converts a tf Quaternion into a KDL Rotation.
ROS_DEPRECATED void VectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k)
Converts a tf Vector3 into a KDL Vector.
ROS_DEPRECATED geometry_msgs::Pose addDelta(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist, const double &t)
Starting from a Pose from A to B, apply a Twist with reference frame A and reference point B...
ROS_DEPRECATED void QuaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t)
Converts a tf Quaternion into a KDL Rotation.
ROS_DEPRECATED void VectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t)
Converts a tf Vector3 into a KDL Vector.