Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef CONVERSIONS_TF_KDL_H
00031 #define CONVERSIONS_TF_KDL_H
00032
00033 #include "kdl_conversions/kdl_msg.h"
00034 #include "tf/transform_datatypes.h"
00035 #include "kdl/frames.hpp"
00036
00037 #include <geometry_msgs/Pose.h>
00038 #include <geometry_msgs/Twist.h>
00039
00040 namespace tf
00041 {
00042
00044 void poseTFToKDL(const tf::Pose &t, KDL::Frame &k);
00045
00047 void poseKDLToTF(const KDL::Frame &k, tf::Pose &t);
00048
00050 void quaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k);
00051
00053 void quaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t);
00054
00056 void transformTFToKDL(const tf::Transform &t, KDL::Frame &k);
00057
00059 void transformKDLToTF(const KDL::Frame &k, tf::Transform &t);
00060
00062 void vectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k);
00063
00065 void vectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t);
00066
00067
00069 geometry_msgs::Pose addDelta(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist, const double &t) __attribute__((deprecated));
00070
00071
00073 void PoseTFToKDL(const tf::Pose &t, KDL::Frame &k) __attribute__((deprecated));
00074 void inline PoseTFToKDL(const tf::Pose &t, KDL::Frame &k) {poseTFToKDL(t, k);};
00075
00077 void PoseKDLToTF(const KDL::Frame &k, tf::Pose &t) __attribute__((deprecated));
00078 void inline PoseKDLToTF(const KDL::Frame &k, tf::Pose &t) {poseKDLToTF(k, t);};
00079
00081 void QuaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k) __attribute__((deprecated));
00082 void inline QuaternionTFToKDL(const tf::Quaternion &t, KDL::Rotation &k) {quaternionTFToKDL(t, k);};
00083
00085 void QuaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t) __attribute__((deprecated));
00086 void inline QuaternionKDLToTF(const KDL::Rotation &k, tf::Quaternion &t) {quaternionKDLToTF(k, t);};
00087
00089 void TransformTFToKDL(const tf::Transform &t, KDL::Frame &k) __attribute__((deprecated));
00090 void inline TransformTFToKDL(const tf::Transform &t, KDL::Frame &k) {transformTFToKDL(t, k);};
00091
00093 void TransformKDLToTF(const KDL::Frame &k, tf::Transform &t) __attribute__((deprecated));
00094 void inline TransformKDLToTF(const KDL::Frame &k, tf::Transform &t) {transformKDLToTF(k, t);};
00095
00097 void VectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k) __attribute__((deprecated));
00098 void inline VectorTFToKDL(const tf::Vector3 &t, KDL::Vector &k) {vectorTFToKDL(t, k);};
00099
00101 void VectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t) __attribute__((deprecated));
00102 void inline VectorKDLToTF(const KDL::Vector &k, tf::Vector3 &t) {vectorKDLToTF(k, t);};
00103
00104
00105 }
00106
00107 #endif