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 Affine3d into a Pose message. | |
void | poseEigenToMsg (const Eigen::Isometry3d &e, geometry_msgs::Pose &m) |
Converts an Eigen Isometry3d into a Pose message. | |
void | poseMsgToEigen (const geometry_msgs::Pose &m, Eigen::Affine3d &e) |
Converts a Pose message into an Eigen Affine3d. | |
void | poseMsgToEigen (const geometry_msgs::Pose &m, Eigen::Isometry3d &e) |
Converts a Pose message into an Eigen Isometry3d. | |
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 Affine3d into a KDL frame. | |
void | transformEigenToKDL (const Eigen::Isometry3d &e, KDL::Frame &k) |
Converts an Eigen Isometry3d into a KDL frame. | |
void | transformEigenToMsg (const Eigen::Affine3d &e, geometry_msgs::Transform &m) |
Converts an Eigen Affine3d into a Transform message. | |
void | transformEigenToMsg (const Eigen::Isometry3d &e, geometry_msgs::Transform &m) |
Converts an Eigen Isometry3d into a Transform message. | |
void | transformKDLToEigen (const KDL::Frame &k, Eigen::Affine3d &e) |
Converts a KDL frame into an Eigen Affine3d. | |
void | transformKDLToEigen (const KDL::Frame &k, Eigen::Isometry3d &e) |
Converts a KDL frame into an Eigen Isometry3d. | |
void | transformMsgToEigen (const geometry_msgs::Transform &m, Eigen::Affine3d &e) |
Converts a Transform message into an Eigen Affine3d. | |
void | transformMsgToEigen (const geometry_msgs::Transform &m, Eigen::Isometry3d &e) |
Converts a Transform message into an Eigen Isometry3d. | |
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::Vector &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, 3, 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. |
void tf::matrixEigenToMsg | ( | const Eigen::MatrixBase< Derived > & | e, |
std_msgs::Float64MultiArray & | m | ||
) |
Converts an Eigen matrix into a Float64MultiArray message.
Definition at line 107 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 Affine3d into a Pose message.
Definition at line 123 of file eigen_msg.cpp.
void tf::poseEigenToMsg | ( | const Eigen::Isometry3d & | e, |
geometry_msgs::Pose & | m | ||
) |
Converts an Eigen Isometry3d into a Pose message.
Definition at line 128 of file eigen_msg.cpp.
void tf::poseMsgToEigen | ( | const geometry_msgs::Pose & | m, |
Eigen::Affine3d & | e | ||
) |
Converts a Pose message into an Eigen Affine3d.
Definition at line 113 of file eigen_msg.cpp.
void tf::poseMsgToEigen | ( | const geometry_msgs::Pose & | m, |
Eigen::Isometry3d & | e | ||
) |
Converts a Pose message into an Eigen Isometry3d.
Definition at line 118 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 138 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 133 of file eigen_msg.cpp.
void tf::transformEigenToKDL | ( | const Eigen::Affine3d & | e, |
KDL::Frame & | k | ||
) |
Converts an Eigen Affine3d into a KDL frame.
Definition at line 90 of file eigen_kdl.cpp.
void tf::transformEigenToKDL | ( | const Eigen::Isometry3d & | e, |
KDL::Frame & | k | ||
) |
Converts an Eigen Isometry3d into a KDL frame.
Definition at line 95 of file eigen_kdl.cpp.
void tf::transformEigenToMsg | ( | const Eigen::Affine3d & | e, |
geometry_msgs::Transform & | m | ||
) |
Converts an Eigen Affine3d into a Transform message.
Definition at line 156 of file eigen_msg.cpp.
void tf::transformEigenToMsg | ( | const Eigen::Isometry3d & | e, |
geometry_msgs::Transform & | m | ||
) |
Converts an Eigen Isometry3d into a Transform message.
Definition at line 161 of file eigen_msg.cpp.
void tf::transformKDLToEigen | ( | const KDL::Frame & | k, |
Eigen::Affine3d & | e | ||
) |
Converts a KDL frame into an Eigen Affine3d.
Definition at line 80 of file eigen_kdl.cpp.
void tf::transformKDLToEigen | ( | const KDL::Frame & | k, |
Eigen::Isometry3d & | e | ||
) |
Converts a KDL frame into an Eigen Isometry3d.
Definition at line 85 of file eigen_kdl.cpp.
void tf::transformMsgToEigen | ( | const geometry_msgs::Transform & | m, |
Eigen::Affine3d & | e | ||
) |
Converts a Transform message into an Eigen Affine3d.
Definition at line 146 of file eigen_msg.cpp.
void tf::transformMsgToEigen | ( | const geometry_msgs::Transform & | m, |
Eigen::Isometry3d & | e | ||
) |
Converts a Transform message into an Eigen Isometry3d.
Definition at line 151 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 100 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 190 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 106 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 180 of file eigen_msg.cpp.
void tf::vectorEigenToKDL | ( | const Eigen::Matrix< double, 3, 1 > & | e, |
KDL::Vector & | k | ||
) |
Converts an Eigen matrix into a KDL vector.
Definition at line 112 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 173 of file eigen_msg.cpp.
void tf::vectorKDLToEigen | ( | const KDL::Vector & | k, |
Eigen::Matrix< double, 3, 1 > & | e | ||
) |
Converts a KDL vector into an Eigen matrix.
Definition at line 117 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 166 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 129 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 210 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 123 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 200 of file eigen_msg.cpp.