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 "tf_conversions/tf_eigen.h"
00031
00032 namespace tf {
00033
00034 void VectorTFToEigen(const tf::Vector3& t, Eigen::Vector3d& k)
00035 {
00036 k(0) = t[0];
00037 k(1) = t[1];
00038 k(2) = t[2];
00039 };
00040
00041 void VectorEigenToTF(const Eigen::Vector3d& k, tf::Vector3& t)
00042 {
00043 t[0] = k(0);
00044 t[1] = k(1);
00045 t[2] = k(2);
00046 }
00047
00048 void RotationTFToEigen(const tf::Quaternion& t, Eigen::Quaterniond& k)
00049 {
00050 Eigen::Quaterniond m(t[3],t[0],t[1],t[2]);
00051 k = m;
00052 };
00053
00054 void RotationEigenToTF(const Eigen::Quaterniond& k, tf::Quaternion& t)
00055 {
00056 t[0] = k.x();
00057 t[1] = k.y();
00058 t[2] = k.z();
00059 t[3] = k.w();
00060 }
00061
00062 void TransformTFToEigen(const tf::Transform &t, Eigen::Affine3d &k)
00063 {
00064 for(int i=0; i<3; i++)
00065 {
00066 k.matrix()(i,3) = t.getOrigin()[i];
00067 for(int j=0; j<3; j++)
00068 {
00069 k.matrix()(i,j) = t.getBasis()[i][j];
00070 }
00071 }
00072
00073 for (int col = 0 ; col < 3; col ++)
00074 k.matrix()(3, col) = 0;
00075 k.matrix()(3,3) = 1;
00076
00077 };
00078
00079 void TransformEigenToTF(const Eigen::Affine3d &k, tf::Transform &t)
00080 {
00081 t.setOrigin(tf::Vector3(k.matrix()(0,3), k.matrix()(1,3), k.matrix()(2,3)));
00082 t.setBasis(tf::Matrix3x3(k.matrix()(0,0), k.matrix()(0,1),k.matrix()(0,2),k.matrix()(1,0), k.matrix()(1,1),k.matrix()(1,2),k.matrix()(2,0), k.matrix()(2,1),k.matrix()(2,2)));
00083 };
00084 }