Namespaces | Functions
tf2_eigen.h File Reference
#include <tf2/convert.h>
#include <Eigen/Geometry>
#include <geometry_msgs/QuaternionStamped.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Twist.h>
Include dependency graph for tf2_eigen.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 Eigen
 
 tf2
 

Functions

template<>
void tf2::doTransform (const Eigen::Vector3d &t_in, Eigen::Vector3d &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an Eigen-specific Vector3d type. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this functions rely on the existence of a time stamp and a frame id in the type which should get transformed. More...
 
template<>
void tf2::doTransform (const tf2::Stamped< Eigen::Vector3d > &t_in, tf2::Stamped< Eigen::Vector3d > &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an Eigen-specific Vector3d type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const Eigen::Affine3d &t_in, Eigen::Affine3d &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs Transform to an Eigen Affine3d transform. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this function relies on the existence of a time stamp and a frame id in the type which should get transformed. More...
 
template<>
void tf2::doTransform (const Eigen::Isometry3d &t_in, Eigen::Isometry3d &t_out, const geometry_msgs::TransformStamped &transform)
 
template<>
void tf2::doTransform (const Eigen::Quaterniond &t_in, Eigen::Quaterniond &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an Eigen-specific Quaterniond type. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this functions rely on the existence of a time stamp and a frame id in the type which should get transformed. More...
 
template<>
void tf2::doTransform (const tf2::Stamped< Eigen::Quaterniond > &t_in, tf2::Stamped< Eigen::Quaterniond > &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an Eigen-specific Quaterniond type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const tf2::Stamped< Eigen::Affine3d > &t_in, tf2::Stamped< Eigen::Affine3d > &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an Eigen Affine3d transform. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this function relies on the existence of a time stamp and a frame id in the type which should get transformed. More...
 
template<>
void tf2::doTransform (const tf2::Stamped< Eigen::Isometry3d > &t_in, tf2::Stamped< Eigen::Isometry3d > &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an Eigen Isometry transform. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this function relies on the existence of a time stamp and a frame id in the type which should get transformed. More...
 
geometry_msgs::TransformStamped tf2::eigenToTransform (const Eigen::Affine3d &T)
 Convert an Eigen Affine3d transform to the equivalent geometry_msgs message type. More...
 
geometry_msgs::TransformStamped tf2::eigenToTransform (const Eigen::Isometry3d &T)
 Convert an Eigen Isometry3d transform to the equivalent geometry_msgs message type. More...
 
void tf2::fromMsg (const geometry_msgs::Point &msg, Eigen::Vector3d &out)
 Convert a Point message type to a Eigen-specific Vector3d type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Vector3 &msg, Eigen::Vector3d &out)
 Convert a Vector3 message type to a Eigen-specific Vector3d type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::PointStamped &msg, tf2::Stamped< Eigen::Vector3d > &out)
 Convert a PointStamped message type to a stamped Eigen-specific Vector3d type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Quaternion &msg, Eigen::Quaterniond &out)
 Convert a Quaternion message type to a Eigen-specific Quaterniond type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::QuaternionStamped &msg, Stamped< Eigen::Quaterniond > &out)
 Convert a QuaternionStamped message type to a stamped Eigen-specific Quaterniond type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Pose &msg, Eigen::Affine3d &out)
 Convert a Pose message transform type to a Eigen Affine3d. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Pose &msg, Eigen::Isometry3d &out)
 Convert a Pose message transform type to a Eigen Isometry3d. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Twist &msg, Eigen::Matrix< double, 6, 1 > &out)
 Convert a Twist message transform type to a Eigen 6x1 Matrix. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< Eigen::Affine3d > &out)
 Convert a Pose message transform type to a stamped Eigen Affine3d. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< Eigen::Isometry3d > &out)
 
void Eigen::fromMsg (const geometry_msgs::Point &msg, Eigen::Vector3d &out)
 
void Eigen::fromMsg (const geometry_msgs::Pose &msg, Eigen::Affine3d &out)
 
void Eigen::fromMsg (const geometry_msgs::Pose &msg, Eigen::Isometry3d &out)
 
void Eigen::fromMsg (const geometry_msgs::Quaternion &msg, Eigen::Quaterniond &out)
 
void Eigen::fromMsg (const geometry_msgs::Twist &msg, Eigen::Matrix< double, 6, 1 > &out)
 
geometry_msgs::Point tf2::toMsg (const Eigen::Vector3d &in)
 Convert a Eigen Vector3d type to a Point message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Vector3 & tf2::toMsg (const Eigen::Vector3d &in, geometry_msgs::Vector3 &out)
 Convert an Eigen Vector3d type to a Vector3 message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PointStamped tf2::toMsg (const tf2::Stamped< Eigen::Vector3d > &in)
 Convert a stamped Eigen Vector3d type to a PointStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Quaternion tf2::toMsg (const Eigen::Quaterniond &in)
 Convert a Eigen Quaterniond type to a Quaternion message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::QuaternionStamped tf2::toMsg (const Stamped< Eigen::Quaterniond > &in)
 Convert a stamped Eigen Quaterniond type to a QuaternionStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Pose tf2::toMsg (const Eigen::Affine3d &in)
 Convert a Eigen Affine3d transform type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Pose tf2::toMsg (const Eigen::Isometry3d &in)
 Convert a Eigen Isometry3d transform type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Twist tf2::toMsg (const Eigen::Matrix< double, 6, 1 > &in)
 Convert a Eigen 6x1 Matrix type to a Twist message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseStamped tf2::toMsg (const tf2::Stamped< Eigen::Affine3d > &in)
 Convert a stamped Eigen Affine3d transform type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseStamped tf2::toMsg (const tf2::Stamped< Eigen::Isometry3d > &in)
 
geometry_msgs::Pose Eigen::toMsg (const Eigen::Affine3d &in)
 
geometry_msgs::Pose Eigen::toMsg (const Eigen::Isometry3d &in)
 
geometry_msgs::Point Eigen::toMsg (const Eigen::Vector3d &in)
 
geometry_msgs::Quaternion Eigen::toMsg (const Eigen::Quaterniond &in)
 
geometry_msgs::Twist Eigen::toMsg (const Eigen::Matrix< double, 6, 1 > &in)
 
Eigen::Isometry3d tf2::transformToEigen (const geometry_msgs::Transform &t)
 Convert a timestamped transform to the equivalent Eigen data type. More...
 
Eigen::Isometry3d tf2::transformToEigen (const geometry_msgs::TransformStamped &t)
 Convert a timestamped transform to the equivalent Eigen data type. More...
 


tf2_eigen
Author(s): Koji Terada
autogenerated on Mon Jun 27 2022 02:43:11