Functions
tf Namespace Reference

Functions

template<class Derived >
void matrixEigenToMsg (const Eigen::MatrixBase< Derived > &e, std_msgs::Float64MultiArray &m)
 Converts an Eigen matrix into a Float64MultiArray message.
void pointEigenToMsg (const Eigen::Vector3d &e, geometry_msgs::Point &m)
 Converts an Eigen Vector into a Point message.
void pointMsgToEigen (const geometry_msgs::Point &m, Eigen::Vector3d &e)
 Converts a Point message into an Eigen Vector.
void poseEigenToMsg (const Eigen::Affine3d &e, geometry_msgs::Pose &m)
 Converts an Eigen transform into a Pose message.
void poseMsgToEigen (const geometry_msgs::Pose &m, Eigen::Affine3d &e)
 Converts a Pose message into an Eigen Transform.
void quaternionEigenToKDL (const Eigen::Quaterniond &e, KDL::Rotation &k)
 Converts an Eigen quaternion into a KDL rotation.
void quaternionEigenToMsg (const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m)
 Converts an Eigen Quaternion into a Quaternion message.
void quaternionKDLToEigen (const KDL::Rotation &k, Eigen::Quaterniond &e)
 Converts a KDL rotation into an Eigen quaternion.
void quaternionMsgToEigen (const geometry_msgs::Quaternion &m, Eigen::Quaterniond &e)
 Converts a Quaternion message into an Eigen Quaternion.
void transformEigenToKDL (const Eigen::Affine3d &e, KDL::Frame &k)
 Converts an Eigen transform into a KDL frame.
void transformEigenToMsg (const Eigen::Affine3d &e, geometry_msgs::Transform &m)
 Converts an Eigen transform into a Transform message.
void transformKDLToEigen (const KDL::Frame &k, Eigen::Affine3d &e)
 Converts a KDL frame into an Eigen transform.
void transformMsgToEigen (const geometry_msgs::Transform &m, Eigen::Affine3d &e)
 Converts a Transform message into an Eigen Transform.
void twistEigenToKDL (const Eigen::Matrix< double, 6, 1 > &e, KDL::Twist &k)
 Converts an Eigen matrix into a KDL Twist.
void twistEigenToMsg (const Eigen::Matrix< double, 6, 1 > &e, geometry_msgs::Twist &m)
 Converts an Eigen matrix into a Twist message.
void twistKDLToEigen (const KDL::Twist &k, Eigen::Matrix< double, 6, 1 > &e)
 Converts a KDL twist into an Eigen matrix.
void twistMsgToEigen (const geometry_msgs::Twist &m, Eigen::Matrix< double, 6, 1 > &e)
 Converts a Twist message into an Eigen matrix.
void vectorEigenToKDL (const Eigen::Matrix< double, 3, 1 > &e, KDL::Twist &k)
 Converts an Eigen matrix into a KDL vector.
void vectorEigenToMsg (const Eigen::Vector3d &e, geometry_msgs::Vector3 &m)
 Converts an Eigen Vector into a Vector message.
void vectorKDLToEigen (const KDL::Vector &k, Eigen::Matrix< double, 6, 1 > &e)
 Converts a KDL vector into an Eigen matrix.
void vectorMsgToEigen (const geometry_msgs::Vector3 &m, Eigen::Vector3d &e)
 Converts a Vector message into an Eigen Vector.
void wrenchEigenToKDL (const Eigen::Matrix< double, 6, 1 > &e, KDL::Wrench &k)
 Converts an Eigen matrix into a KDL wrench.
void wrenchEigenToMsg (const Eigen::Matrix< double, 6, 1 > &e, geometry_msgs::Wrench &m)
 Converts an Eigen matrix into a Wrench message.
void wrenchKDLToEigen (const KDL::Wrench &k, Eigen::Matrix< double, 6, 1 > &e)
 Converts a KDL wrench into an Eigen matrix.
void wrenchMsgToEigen (const geometry_msgs::Wrench &m, Eigen::Matrix< double, 6, 1 > &e)
 Converts a Wrench message into an Eigen matrix.

Function Documentation

template<class Derived >
void tf::matrixEigenToMsg ( const Eigen::MatrixBase< Derived > &  e,
std_msgs::Float64MultiArray &  m 
)

Converts an Eigen matrix into a Float64MultiArray message.

Definition at line 95 of file eigen_msg.h.

void tf::pointEigenToMsg ( const Eigen::Vector3d &  e,
geometry_msgs::Point &  m 
)

Converts an Eigen Vector into a Point message.

Definition at line 42 of file eigen_msg.cpp.

void tf::pointMsgToEigen ( const geometry_msgs::Point &  m,
Eigen::Vector3d &  e 
)

Converts a Point message into an Eigen Vector.

Definition at line 35 of file eigen_msg.cpp.

void tf::poseEigenToMsg ( const Eigen::Affine3d &  e,
geometry_msgs::Pose &  m 
)

Converts an Eigen transform into a Pose message.

Definition at line 60 of file eigen_msg.cpp.

void tf::poseMsgToEigen ( const geometry_msgs::Pose &  m,
Eigen::Affine3d &  e 
)

Converts a Pose message into an Eigen Transform.

Definition at line 49 of file eigen_msg.cpp.

void tf::quaternionEigenToKDL ( const Eigen::Quaterniond &  e,
KDL::Rotation k 
)

Converts an Eigen quaternion into a KDL rotation.

Definition at line 45 of file eigen_kdl.cpp.

void tf::quaternionEigenToMsg ( const Eigen::Quaterniond &  e,
geometry_msgs::Quaternion &  m 
)

Converts an Eigen Quaternion into a Quaternion message.

Definition at line 83 of file eigen_msg.cpp.

void tf::quaternionKDLToEigen ( const KDL::Rotation k,
Eigen::Quaterniond &  e 
)

Converts a KDL rotation into an Eigen quaternion.

Definition at line 34 of file eigen_kdl.cpp.

void tf::quaternionMsgToEigen ( const geometry_msgs::Quaternion &  m,
Eigen::Quaterniond &  e 
)

Converts a Quaternion message into an Eigen Quaternion.

Definition at line 78 of file eigen_msg.cpp.

void tf::transformEigenToKDL ( const Eigen::Affine3d &  e,
KDL::Frame k 
)

Converts an Eigen transform into a KDL frame.

Definition at line 67 of file eigen_kdl.cpp.

void tf::transformEigenToMsg ( const Eigen::Affine3d &  e,
geometry_msgs::Transform &  m 
)

Converts an Eigen transform into a Transform message.

Definition at line 102 of file eigen_msg.cpp.

void tf::transformKDLToEigen ( const KDL::Frame k,
Eigen::Affine3d &  e 
)

Converts a KDL frame into an Eigen transform.

Definition at line 50 of file eigen_kdl.cpp.

void tf::transformMsgToEigen ( const geometry_msgs::Transform &  m,
Eigen::Affine3d &  e 
)

Converts a Transform message into an Eigen Transform.

Definition at line 91 of file eigen_msg.cpp.

void tf::twistEigenToKDL ( const Eigen::Matrix< double, 6, 1 > &  e,
KDL::Twist k 
)

Converts an Eigen matrix into a KDL Twist.

Definition at line 75 of file eigen_kdl.cpp.

void tf::twistEigenToMsg ( const Eigen::Matrix< double, 6, 1 > &  e,
geometry_msgs::Twist &  m 
)

Converts an Eigen matrix into a Twist message.

Definition at line 144 of file eigen_msg.cpp.

void tf::twistKDLToEigen ( const KDL::Twist k,
Eigen::Matrix< double, 6, 1 > &  e 
)

Converts a KDL twist into an Eigen matrix.

Definition at line 81 of file eigen_kdl.cpp.

void tf::twistMsgToEigen ( const geometry_msgs::Twist &  m,
Eigen::Matrix< double, 6, 1 > &  e 
)

Converts a Twist message into an Eigen matrix.

Definition at line 134 of file eigen_msg.cpp.

void tf::vectorEigenToKDL ( const Eigen::Matrix< double, 3, 1 > &  e,
KDL::Twist k 
)

Converts an Eigen matrix into a KDL vector.

Definition at line 87 of file eigen_kdl.cpp.

void tf::vectorEigenToMsg ( const Eigen::Vector3d &  e,
geometry_msgs::Vector3 &  m 
)

Converts an Eigen Vector into a Vector message.

Definition at line 127 of file eigen_msg.cpp.

void tf::vectorKDLToEigen ( const KDL::Vector k,
Eigen::Matrix< double, 6, 1 > &  e 
)

Converts a KDL vector into an Eigen matrix.

Definition at line 92 of file eigen_kdl.cpp.

void tf::vectorMsgToEigen ( const geometry_msgs::Vector3 &  m,
Eigen::Vector3d &  e 
)

Converts a Vector message into an Eigen Vector.

Definition at line 120 of file eigen_msg.cpp.

void tf::wrenchEigenToKDL ( const Eigen::Matrix< double, 6, 1 > &  e,
KDL::Wrench k 
)

Converts an Eigen matrix into a KDL wrench.

Definition at line 104 of file eigen_kdl.cpp.

void tf::wrenchEigenToMsg ( const Eigen::Matrix< double, 6, 1 > &  e,
geometry_msgs::Wrench &  m 
)

Converts an Eigen matrix into a Wrench message.

Definition at line 164 of file eigen_msg.cpp.

void tf::wrenchKDLToEigen ( const KDL::Wrench k,
Eigen::Matrix< double, 6, 1 > &  e 
)

Converts a KDL wrench into an Eigen matrix.

Definition at line 98 of file eigen_kdl.cpp.

void tf::wrenchMsgToEigen ( const geometry_msgs::Wrench &  m,
Eigen::Matrix< double, 6, 1 > &  e 
)

Converts a Wrench message into an Eigen matrix.

Definition at line 154 of file eigen_msg.cpp.



eigen_conversions
Author(s): Stuart Glaser, Adam Leeper
autogenerated on Mon Oct 6 2014 00:11:59