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
00031
00032
00033
00034 #ifndef EIGEN_MSG_CONVERSIONS_H
00035 #define EIGEN_MSG_CONVERSIONS_H
00036
00037 #include <std_msgs/Float64MultiArray.h>
00038 #include <geometry_msgs/Point.h>
00039 #include <geometry_msgs/Pose.h>
00040 #include <geometry_msgs/Quaternion.h>
00041 #include <geometry_msgs/Transform.h>
00042 #include <geometry_msgs/Twist.h>
00043 #include <geometry_msgs/Vector3.h>
00044 #include <geometry_msgs/Wrench.h>
00045
00046 #include <Eigen/Core>
00047 #include <Eigen/Geometry>
00048
00049 namespace tf {
00050
00052 void pointMsgToEigen(const geometry_msgs::Point &m, Eigen::Vector3d &e);
00053
00055 void pointEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Point &m);
00056
00058 void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e);
00059
00061 void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m);
00062
00064 void quaternionMsgToEigen(const geometry_msgs::Quaternion &m, Eigen::Quaterniond &e);
00065
00067 void quaternionEigenToMsg(const Eigen::Quaterniond &e, geometry_msgs::Quaternion &m);
00068
00070 void transformMsgToEigen(const geometry_msgs::Transform &m, Eigen::Affine3d &e);
00071
00073 void transformEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Transform &m);
00074
00076 void twistMsgToEigen(const geometry_msgs::Twist &m, Eigen::Matrix<double,6,1> &e);
00077
00079 void twistEigenToMsg(const Eigen::Matrix<double,6,1> &e, geometry_msgs::Twist &m);
00080
00082 void vectorMsgToEigen(const geometry_msgs::Vector3 &m, Eigen::Vector3d &e);
00083
00085 void vectorEigenToMsg(const Eigen::Vector3d &e, geometry_msgs::Vector3 &m);
00086
00088 void wrenchMsgToEigen(const geometry_msgs::Wrench &m, Eigen::Matrix<double,6,1> &e);
00089
00091 void wrenchEigenToMsg(const Eigen::Matrix<double,6,1> &e, geometry_msgs::Wrench &m);
00092
00094 template <class Derived>
00095 void matrixEigenToMsg(const Eigen::MatrixBase<Derived> &e, std_msgs::Float64MultiArray &m)
00096 {
00097 if (m.layout.dim.size() != 2)
00098 m.layout.dim.resize(2);
00099 m.layout.dim[0].stride = e.rows() * e.cols();
00100 m.layout.dim[0].size = e.rows();
00101 m.layout.dim[1].stride = e.cols();
00102 m.layout.dim[1].size = e.cols();
00103 if ((int)m.data.size() != e.size())
00104 m.data.resize(e.size());
00105 int ii = 0;
00106 for (int i = 0; i < e.rows(); ++i)
00107 for (int j = 0; j < e.cols(); ++j)
00108 m.data[ii++] = e.coeff(i, j);
00109 }
00110
00111 }
00112
00113 #endif