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/PoseStamped.h>
00039 #include <geometry_msgs/Pose.h>
00040 #include <geometry_msgs/Twist.h>
00041 #include <geometry_msgs/Wrench.h>
00042
00043 #include <Eigen/Core>
00044 #include <Eigen/Geometry>
00045
00046 namespace tf {
00047
00049 void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e);
00050
00052 void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m);
00053
00055 void twistMsgToEigen(const geometry_msgs::Twist &m, Eigen::Matrix<double,6,1> &e);
00056
00058 void twistEigenToMsg(const Eigen::Matrix<double,6,1> &e, geometry_msgs::Twist &m);
00059
00061 void wrenchMsgToEigen(const geometry_msgs::Wrench &m, Eigen::Matrix<double,6,1> &e);
00062
00064 void wrenchEigenToMsg(const Eigen::Matrix<double,6,1> &e, geometry_msgs::Wrench &m);
00065
00067 template <class Derived>
00068 void matrixEigenToMsg(const Eigen::MatrixBase<Derived> &e, std_msgs::Float64MultiArray &m)
00069 {
00070 if (m.layout.dim.size() != 2)
00071 m.layout.dim.resize(2);
00072 m.layout.dim[0].stride = e.rows() * e.cols();
00073 m.layout.dim[0].size = e.rows();
00074 m.layout.dim[1].stride = e.cols();
00075 m.layout.dim[1].size = e.cols();
00076 if ((int)m.data.size() != e.size())
00077 m.data.resize(e.size());
00078 int ii = 0;
00079 for (int i = 0; i < e.rows(); ++i)
00080 for (int j = 0; j < e.cols(); ++j)
00081 m.data[ii++] = e.coeff(i, j);
00082 }
00083
00084 }
00085
00086 #endif