1 #ifndef GEOMETRY_CONVERSIONS_EIGEN_H
2 #define GEOMETRY_CONVERSIONS_EIGEN_H
4 #include <geometry_msgs/PoseStamped.h>
5 #include <geometry_msgs/Vector3.h>
8 #include <Eigen/Geometry>
17 geometry_msgs::Point fromEigen(
const Eigen::Vector3d& what);
19 geometry_msgs::Vector3 fromEigenVec(
const Eigen::Vector3d& what);
21 Eigen::Vector3d toEigen(
const geometry_msgs::Point& what);
23 Eigen::Vector3d toEigen(
const geometry_msgs::Vector3& what);
25 Eigen::Matrix<double, 6, 6> toEigenMatrix(
const boost::array<double, 36>& what);
27 geometry_msgs::Quaternion fromEigen(
const Eigen::Quaterniond& what);
29 Eigen::Quaterniond toEigen(
const geometry_msgs::Quaternion& what);
36 #endif // GEOMETRY_CONVERSIONS_EIGEN_H