|  | 
| void | tf::quaternionEigenToKDL (const Eigen::Quaterniond &e, KDL::Rotation &k) | 
|  | Converts an Eigen quaternion into a KDL rotation.  More... 
 | 
|  | 
| void | tf::quaternionKDLToEigen (const KDL::Rotation &k, Eigen::Quaterniond &e) | 
|  | Converts a KDL rotation into an Eigen quaternion.  More... 
 | 
|  | 
| void | tf::transformEigenToKDL (const Eigen::Affine3d &e, KDL::Frame &k) | 
|  | Converts an Eigen Affine3d into a KDL frame.  More... 
 | 
|  | 
| void | tf::transformEigenToKDL (const Eigen::Isometry3d &e, KDL::Frame &k) | 
|  | Converts an Eigen Isometry3d into a KDL frame.  More... 
 | 
|  | 
| void | tf::transformKDLToEigen (const KDL::Frame &k, Eigen::Affine3d &e) | 
|  | Converts a KDL frame into an Eigen Affine3d.  More... 
 | 
|  | 
| void | tf::transformKDLToEigen (const KDL::Frame &k, Eigen::Isometry3d &e) | 
|  | Converts a KDL frame into an Eigen Isometry3d.  More... 
 | 
|  | 
| void | tf::twistEigenToKDL (const Eigen::Matrix< double, 6, 1 > &e, KDL::Twist &k) | 
|  | Converts an Eigen matrix into a KDL Twist.  More... 
 | 
|  | 
| void | tf::twistKDLToEigen (const KDL::Twist &k, Eigen::Matrix< double, 6, 1 > &e) | 
|  | Converts a KDL twist into an Eigen matrix.  More... 
 | 
|  | 
| void | tf::vectorEigenToKDL (const Eigen::Matrix< double, 3, 1 > &e, KDL::Vector &k) | 
|  | Converts an Eigen matrix into a KDL vector.  More... 
 | 
|  | 
| void | tf::vectorKDLToEigen (const KDL::Vector &k, Eigen::Matrix< double, 3, 1 > &e) | 
|  | Converts a KDL vector into an Eigen matrix.  More... 
 | 
|  | 
| void | tf::wrenchEigenToKDL (const Eigen::Matrix< double, 6, 1 > &e, KDL::Wrench &k) | 
|  | Converts an Eigen matrix into a KDL wrench.  More... 
 | 
|  | 
| void | tf::wrenchKDLToEigen (const KDL::Wrench &k, Eigen::Matrix< double, 6, 1 > &e) | 
|  | Converts a KDL wrench into an Eigen matrix.  More... 
 | 
|  |