2#ifndef GEOMETRY_CONVERSIONS_EIGEN_H
3#define GEOMETRY_CONVERSIONS_EIGEN_H
5#include <geometry_msgs/msg/vector3.hpp>
6#include <geometry_msgs/msg/pose_stamped.hpp>
7#include <geometry_msgs/msg/vector3.h>
10#include <Eigen/Geometry>
19 geometry_msgs::msg::Point fromEigen(
const Eigen::Vector3d& what);
21 geometry_msgs::msg::Vector3 fromEigenVec(
const Eigen::Vector3d& what);
23 Eigen::Vector3d toEigen(
const geometry_msgs::msg::Point& what);
25 Eigen::Vector3d toEigen(
const geometry_msgs::msg::Vector3& what);
27 Eigen::Matrix<double, 6, 6> toEigenMatrix(
const std::array<double, 36>& what);
29 geometry_msgs::msg::Quaternion fromEigen(
const Eigen::Quaterniond& what);
31 Eigen::Quaterniond toEigen(
const geometry_msgs::msg::Quaternion& what);
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24