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
00031
00032 #ifndef CONVERSIONS_KDL_MSG_H
00033 #define CONVERSIONS_KDL_MSG_H
00034
00035 #include "kdl/frames.hpp"
00036 #include <geometry_msgs/Point.h>
00037 #include <geometry_msgs/Pose.h>
00038 #include <geometry_msgs/Quaternion.h>
00039 #include <geometry_msgs/Transform.h>
00040 #include <geometry_msgs/Twist.h>
00041 #include <geometry_msgs/Vector3.h>
00042 #include <geometry_msgs/Wrench.h>
00043
00044
00045 namespace tf {
00047
00049 void pointMsgToKDL(const geometry_msgs::Point &m, KDL::Vector &k);
00050
00052 void pointKDLToMsg(const KDL::Vector &k, geometry_msgs::Point &m);
00053
00055 void poseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k);
00056
00058 void poseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m);
00059
00061 void quaternionMsgToKDL(const geometry_msgs::Quaternion &m, KDL::Rotation &k);
00062
00064 void quaternionKDLToMsg(const KDL::Rotation &k, geometry_msgs::Quaternion &m);
00065
00067 void transformMsgToKDL(const geometry_msgs::Transform &m, KDL::Frame &k);
00068
00070 void transformKDLToMsg(const KDL::Frame &k, geometry_msgs::Transform &m);
00071
00073 void twistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k);
00074
00076 void twistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m);
00077
00079 void vectorMsgToKDL(const geometry_msgs::Vector3 &m, KDL::Vector &k);
00080
00082 void vectorKDLToMsg(const KDL::Vector &k, geometry_msgs::Vector3 &m);
00083
00085 void wrenchMsgToKDL(const geometry_msgs::Wrench &m, KDL::Wrench &k);
00086
00088 void wrenchKDLToMsg(const KDL::Wrench &k, geometry_msgs::Wrench &m);
00089
00090
00091
00093 void PoseMsgToKDL(const geometry_msgs::Pose &m, KDL::Frame &k)__attribute__((deprecated));
00094
00096 void PoseKDLToMsg(const KDL::Frame &k, geometry_msgs::Pose &m) __attribute__((deprecated));
00097
00098
00099
00101 void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &k) __attribute__((deprecated));
00102
00104 void TwistKDLToMsg(const KDL::Twist &k, geometry_msgs::Twist &m) __attribute__((deprecated));
00105
00106
00107
00108 }
00109
00110
00111 #endif
00112
00113
00114