Namespaces | Functions
tf_kdl.h File Reference
#include "kdl_conversions/kdl_msg.h"
#include "tf/transform_datatypes.h"
#include "kdl/frames.hpp"
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Twist.h>
Include dependency graph for tf_kdl.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  tf

Functions

geometry_msgs::Pose tf::addDelta (const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist, const double &t) __attribute__((deprecated))
 Starting from a Pose from A to B, apply a Twist with reference frame A and reference point B, during a time t.
void tf::poseKDLToTF (const KDL::Frame &k, tf::Pose &t)
 Converts a KDL Frame into a tf Pose.
void tf::PoseKDLToTF (const KDL::Frame &k, tf::Pose &t) __attribute__((deprecated))
 Converts a KDL Frame into a tf Pose.
void tf::poseTFToKDL (const tf::Pose &t, KDL::Frame &k)
 Converts a tf Pose into a KDL Frame.
void tf::PoseTFToKDL (const tf::Pose &t, KDL::Frame &k) __attribute__((deprecated))
 Converts a tf Pose into a KDL Frame.
void tf::quaternionKDLToTF (const KDL::Rotation &k, tf::Quaternion &t)
 Converts a tf Quaternion into a KDL Rotation.
void tf::QuaternionKDLToTF (const KDL::Rotation &k, tf::Quaternion &t) __attribute__((deprecated))
 Converts a tf Quaternion into a KDL Rotation.
void tf::quaternionTFToKDL (const tf::Quaternion &t, KDL::Rotation &k)
 Converts a tf Quaternion into a KDL Rotation.
void tf::QuaternionTFToKDL (const tf::Quaternion &t, KDL::Rotation &k) __attribute__((deprecated))
 Converts a tf Quaternion into a KDL Rotation.
void tf::transformKDLToTF (const KDL::Frame &k, tf::Transform &t)
 Converts a KDL Frame into a tf Transform.
void tf::TransformKDLToTF (const KDL::Frame &k, tf::Transform &t) __attribute__((deprecated))
 Converts a KDL Frame into a tf Transform.
void tf::transformTFToKDL (const tf::Transform &t, KDL::Frame &k)
 Converts a tf Transform into a KDL Frame.
void tf::TransformTFToKDL (const tf::Transform &t, KDL::Frame &k) __attribute__((deprecated))
 Converts a tf Transform into a KDL Frame.
void tf::vectorKDLToTF (const KDL::Vector &k, tf::Vector3 &t)
 Converts a tf Vector3 into a KDL Vector.
void tf::VectorKDLToTF (const KDL::Vector &k, tf::Vector3 &t) __attribute__((deprecated))
 Converts a tf Vector3 into a KDL Vector.
void tf::vectorTFToKDL (const tf::Vector3 &t, KDL::Vector &k)
 Converts a tf Vector3 into a KDL Vector.
void tf::VectorTFToKDL (const tf::Vector3 &t, KDL::Vector &k) __attribute__((deprecated))
 Converts a tf Vector3 into a KDL Vector.


tf_conversions
Author(s): Tully Foote
autogenerated on Thu Aug 27 2015 13:08:38