37   k.GetQuaternion(e.x(), e.y(), e.z(), e.w());
 
   47   k = KDL::Rotation::Quaternion(e.x(), e.y(), e.z(), e.w());  
 
   52   void transformKDLToEigenImpl(
const KDL::Frame &k, T &e)
 
   55     for (
unsigned int i = 0; i < 3; ++i)
 
   59     for (
unsigned int i = 0; i < 9; ++i)
 
   60       e(i/3, i%3) = k.M.data[i];
 
   70   void transformEigenToKDLImpl(
const T &e, KDL::Frame &k)
 
   72     for (
unsigned int i = 0; i < 3; ++i)
 
   74     for (
unsigned int i = 0; i < 9; ++i)
 
   75       k.M.data[i] = e(i/3, i%3);
 
   82   transformKDLToEigenImpl(k, e);
 
   87   transformKDLToEigenImpl(k, e);
 
   92   transformEigenToKDLImpl(e, k);
 
   97   transformEigenToKDLImpl(e, k);
 
  102   for(
int i = 0; i < 6; ++i)
 
  108   for(
int i = 0; i < 6; ++i)
 
  114   for(
int i = 0; i < 3; ++i)
 
  119   for(
int i = 0; i < 3; ++i)
 
  125   for(
int i = 0; i < 6; ++i)
 
  131   for(
int i = 0; i < 6; ++i)