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 #include "tf_conversions/tf_kdl.h"
00031
00032 namespace tf {
00033
00034 void VectorTFToKDL(const tf::Vector3& t, KDL::Vector& k)
00035 {
00036 k = KDL::Vector(t[0], t[1], t[2]);
00037 }
00038
00039 void RotationTFToKDL(const tf::Quaternion& t, KDL::Rotation& k)
00040 {
00041 k = KDL::Rotation::Quaternion(t[0], t[1], t[2], t[3]);
00042 }
00043
00044 void TransformTFToKDL(const tf::Transform &t, KDL::Frame &k)
00045 {
00046 for (unsigned int i = 0; i < 3; ++i)
00047 k.p[i] = t.getOrigin()[i];
00048 for (unsigned int i = 0; i < 9; ++i)
00049 k.M.data[i] = t.getBasis()[i/3][i%3];
00050 }
00051
00052 void TransformKDLToTF(const KDL::Frame &k, tf::Transform &t)
00053 {
00054 t.setOrigin(tf::Vector3(k.p[0], k.p[1], k.p[2]));
00055 t.setBasis(btMatrix3x3(k.M.data[0], k.M.data[1], k.M.data[2],
00056 k.M.data[3], k.M.data[4], k.M.data[5],
00057 k.M.data[6], k.M.data[7], k.M.data[8]));
00058 }
00059
00060 void PoseTFToKDL(const tf::Pose& t, KDL::Frame& k)
00061 {
00062 for (unsigned int i = 0; i < 3; ++i)
00063 k.p[i] = t.getOrigin()[i];
00064 for (unsigned int i = 0; i < 9; ++i)
00065 k.M.data[i] = t.getBasis()[i/3][i%3];
00066 }
00067
00068 void PoseKDLToTF(const KDL::Frame& k, tf::Pose& t)
00069 {
00070 t.setOrigin(tf::Vector3(k.p[0], k.p[1], k.p[2]));
00071 t.setBasis(btMatrix3x3(k.M.data[0], k.M.data[1], k.M.data[2],
00072 k.M.data[3], k.M.data[4], k.M.data[5],
00073 k.M.data[6], k.M.data[7], k.M.data[8]));
00074 }
00075
00076 void TwistKDLToMsg(const KDL::Twist &t, geometry_msgs::Twist &m)
00077 {
00078 m.linear.x = t.vel[0];
00079 m.linear.y = t.vel[1];
00080 m.linear.z = t.vel[2];
00081 m.angular.x = t.rot[0];
00082 m.angular.y = t.rot[1];
00083 m.angular.z = t.rot[2];
00084 }
00085
00086 void TwistMsgToKDL(const geometry_msgs::Twist &m, KDL::Twist &t)
00087 {
00088 t.vel[0] = m.linear.x;
00089 t.vel[1] = m.linear.y;
00090 t.vel[2] = m.linear.z;
00091 t.rot[0] = m.angular.x;
00092 t.rot[1] = m.angular.y;
00093 t.rot[2] = m.angular.z;
00094 }
00095
00096 void PoseMsgToKDL(const geometry_msgs::Pose &p, KDL::Frame &t)
00097 {
00098 tf::Pose pose_tf;
00099 tf::poseMsgToTF(p,pose_tf);
00100 PoseTFToKDL(pose_tf,t);
00101 }
00102
00103 void PoseKDLToMsg(const KDL::Frame &t, geometry_msgs::Pose &p)
00104 {
00105 tf::Pose pose_tf;
00106 PoseKDLToTF(t,pose_tf);
00107 tf::poseTFToMsg(pose_tf,p);
00108 }
00109
00110 geometry_msgs::Pose addDelta(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist, const double &t)
00111 {
00112 geometry_msgs::Pose result;
00113 KDL::Twist kdl_twist;
00114 KDL::Frame kdl_pose_id, kdl_pose;
00115
00116 PoseMsgToKDL(pose,kdl_pose);
00117 TwistMsgToKDL(twist,kdl_twist);
00118 kdl_pose = KDL::addDelta(kdl_pose_id,kdl_twist,t)*kdl_pose;
00119 PoseKDLToMsg(kdl_pose,result);
00120 return result;
00121 }
00122 }