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 #include <eigen_conversions/eigen_kdl.h>
00031
00032 namespace tf {
00033
00034 void quaternionKDLToEigen(const KDL::Rotation &k, Eigen::Quaterniond &e)
00035 {
00036
00037 k.GetQuaternion(e.x(), e.y(), e.z(), e.w());
00038
00039
00040
00041
00042
00043 }
00044
00045 void quaternionEigenToKDL(const Eigen::Quaterniond &e, KDL::Rotation &k)
00046 {
00047 k = KDL::Rotation::Quaternion(e.x(), e.y(), e.z(), e.w());
00048 }
00049
00050 void transformKDLToEigen(const KDL::Frame &k, Eigen::Affine3d &e)
00051 {
00052
00053 for (unsigned int i = 0; i < 3; ++i)
00054 e(i, 3) = k.p[i];
00055
00056
00057 for (unsigned int i = 0; i < 9; ++i)
00058 e(i/3, i%3) = k.M.data[i];
00059
00060
00061 e(3,0) = 0.0;
00062 e(3,1) = 0.0;
00063 e(3,2) = 0.0;
00064 e(3,3) = 1.0;
00065 }
00066
00067 void transformEigenToKDL(const Eigen::Affine3d &e, KDL::Frame &k)
00068 {
00069 for (unsigned int i = 0; i < 3; ++i)
00070 k.p[i] = e(i, 3);
00071 for (unsigned int i = 0; i < 9; ++i)
00072 k.M.data[i] = e(i/3, i%3);
00073 }
00074
00075 void twistEigenToKDL(const Eigen::Matrix<double, 6, 1> &e, KDL::Twist &k)
00076 {
00077 for(int i = 0; i < 6; ++i)
00078 k[i] = e[i];
00079 }
00080
00081 void twistKDLToEigen(const KDL::Twist &k, Eigen::Matrix<double, 6, 1> &e)
00082 {
00083 for(int i = 0; i < 6; ++i)
00084 e[i] = k[i];
00085 }
00086
00087 void vectorEigenToKDL(const Eigen::Matrix<double, 3, 1> &e, KDL::Twist &k)
00088 {
00089 for(int i = 0; i < 6; ++i)
00090 k[i] = e[i];
00091 }
00092 void vectorKDLToEigen(const KDL::Vector &k, Eigen::Matrix<double, 6, 1> &e)
00093 {
00094 for(int i = 0; i < 3; ++i)
00095 e[i] = k[i];
00096 }
00097
00098 void wrenchKDLToEigen(const KDL::Wrench &k, Eigen::Matrix<double, 6, 1> &e)
00099 {
00100 for(int i = 0; i < 6; ++i)
00101 e[i] = k[i];
00102 }
00103
00104 void wrenchEigenToKDL(const Eigen::Matrix<double, 6, 1> &e, KDL::Wrench &k)
00105 {
00106 for(int i = 0; i < 6; ++i)
00107 k[i] = e[i];
00108 }
00109
00110
00111 }