Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
tf2 Namespace Reference

Namespaces

 cache
 
 impl
 

Classes

class  BufferCore
 
struct  CanTransformAccum
 
class  ConnectivityException
 
class  ExtrapolationException
 
class  InvalidArgumentException
 
class  LookupException
 
class  Matrix3x3
 
struct  Matrix3x3DoubleData
 
struct  Matrix3x3FloatData
 
class  Quaternion
 
class  Stamped
 
class  StaticCache
 
class  TestBufferCore
 
class  tf2Vector4
 
struct  TimeAndFrameIDFrameComparator
 
class  TimeCache
 
class  TimeCacheInterface
 
class  TimeoutException
 
class  Transform
 
struct  TransformAccum
 
struct  TransformDoubleData
 
class  TransformException
 
struct  TransformFloatData
 
class  TransformStorage
 
struct  Vector3DoubleData
 
struct  Vector3FloatData
 

Typedefs

typedef uint32_t CompactFrameID
 
typedef std::pair< ros::Time, CompactFrameIDP_TimeAndFrameID
 
typedef boost::shared_ptr< TimeCacheInterfaceTimeCacheInterfacePtr
 
typedef uint32_t TransformableCallbackHandle
 
typedef uint64_t TransformableRequestHandle
 

Enumerations

enum  TransformableResult
 
enum  WalkEnding
 

Functions

TF2SIMD_FORCE_INLINE tf2Scalar angle (const Quaternion &q1, const Quaternion &q2)
 
TF2SIMD_FORCE_INLINE tf2Scalar angleShortestPath (const Quaternion &q1, const Quaternion &q2)
 
 ATTRIBUTE_ALIGNED16 (class) QuadWord
 
void convert (const A &a, B &b)
 
void convert (const A &a1, A &a2)
 
TF2SIMD_FORCE_INLINE tf2Scalar dot (const Quaternion &q1, const Quaternion &q2)
 
template<>
void 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 doTransform (const Eigen::Isometry3d &t_in, Eigen::Isometry3d &t_out, const geometry_msgs::TransformStamped &transform)
 
template<>
void 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 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...
 
void doTransform (const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
 
template<>
void 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 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...
 
template<>
void 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 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...
 
geometry_msgs::TransformStamped eigenToTransform (const Eigen::Affine3d &T)
 Convert an Eigen Affine3d transform to the equivalent geometry_msgs message type. More...
 
geometry_msgs::TransformStamped eigenToTransform (const Eigen::Isometry3d &T)
 Convert an Eigen Isometry3d transform to the equivalent geometry_msgs message type. More...
 
void fromMsg (const A &, B &b)
 
void 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 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 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 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 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 fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< Eigen::Isometry3d > &out)
 
void 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 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 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 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 getEulerYPR (const A &a, double &yaw, double &pitch, double &roll)
 
const std::string & getFrameId (const T &t)
 
const std::string & getFrameId (const tf2::Stamped< P > &t)
 
const ros::TimegetTimestamp (const T &t)
 
const ros::TimegetTimestamp (const tf2::Stamped< P > &t)
 
getTransformIdentity ()
 
double getYaw (const A &a)
 
TF2SIMD_FORCE_INLINE Quaternion inverse (const Quaternion &q)
 
TF2SIMD_FORCE_INLINE tf2Scalar length (const Quaternion &q)
 
TF2SIMD_FORCE_INLINE Vector3 lerp (const Vector3 &v1, const Vector3 &v2, const tf2Scalar &t)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Matrix3x3 &m, const Vector3 &v)
 
TF2SIMD_FORCE_INLINE Matrix3x3 operator* (const Matrix3x3 &m1, const Matrix3x3 &m2)
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q, const Vector3 &w)
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q1, const Quaternion &q2)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const tf2Scalar &s, const Vector3 &v)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v, const Matrix3x3 &m)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v, const tf2Scalar &s)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const Vector3 &w, const Quaternion &q)
 
TF2SIMD_FORCE_INLINE Vector3 operator+ (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q)
 
TF2SIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v)
 
TF2SIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE Vector3 operator/ (const Vector3 &v, const tf2Scalar &s)
 
TF2SIMD_FORCE_INLINE Vector3 operator/ (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE bool operator== (const Matrix3x3 &m1, const Matrix3x3 &m2)
 
bool operator== (const Stamped< T > &a, const Stamped< T > &b)
 
TF2SIMD_FORCE_INLINE bool operator== (const Transform &t1, const Transform &t2)
 
bool operator> (const TransformStorage &lhs, const TransformStorage &rhs)
 
TF2SIMD_FORCE_INLINE Vector3 quatRotate (const Quaternion &rotation, const Vector3 &v)
 
void setIdentity (geometry_msgs::Transform &tx)
 
TF2SIMD_FORCE_INLINE Quaternion shortestArcQuat (const Vector3 &v0, const Vector3 &v1)
 
TF2SIMD_FORCE_INLINE Quaternion shortestArcQuatNormalize2 (Vector3 &v0, Vector3 &v1)
 
TF2SIMD_FORCE_INLINE Quaternion slerp (const Quaternion &q1, const Quaternion &q2, const tf2Scalar &t)
 
bool startsWithSlash (const std::string &frame_id)
 
std::string stripSlash (const std::string &in)
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Angle (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE Vector3 tf2Cross (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance2 (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Dot (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE void tf2PlaneSpace1 (const Vector3 &n, Vector3 &p, Vector3 &q)
 
TF2SIMD_FORCE_INLINE void tf2SwapScalarEndian (const tf2Scalar &sourceVal, tf2Scalar &destVal)
 
TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec)
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Triple (const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
 
TF2SIMD_FORCE_INLINE void tf2UnSwapVector3Endian (Vector3 &vector)
 
toMsg (const A &a)
 
geometry_msgs::Pose 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 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 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::Quaternion 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::Point 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 & 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::QuaternionStamped 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::PoseStamped 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 toMsg (const tf2::Stamped< Eigen::Isometry3d > &in)
 
geometry_msgs::PointStamped 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...
 
void transformMsgToTF2 (const geometry_msgs::Transform &msg, tf2::Transform &tf2)
 
void transformTF2ToMsg (const tf2::Quaternion &orient, const tf2::Vector3 &pos, geometry_msgs::Transform &msg)
 
void transformTF2ToMsg (const tf2::Quaternion &orient, const tf2::Vector3 &pos, geometry_msgs::TransformStamped &msg, ros::Time stamp, const std::string &frame_id, const std::string &child_frame_id)
 
void transformTF2ToMsg (const tf2::Transform &tf2, geometry_msgs::Transform &msg)
 
void transformTF2ToMsg (const tf2::Transform &tf2, geometry_msgs::TransformStamped &msg, ros::Time stamp, const std::string &frame_id, const std::string &child_frame_id)
 
Eigen::Isometry3d transformToEigen (const geometry_msgs::Transform &t)
 Convert a timestamped transform to the equivalent Eigen data type. More...
 
Eigen::Isometry3d transformToEigen (const geometry_msgs::TransformStamped &t)
 Convert a timestamped transform to the equivalent Eigen data type. More...
 

Variables

 FullPath
 
 Identity
 
static double QUATERNION_NORMALIZATION_TOLERANCE
 
 SourceParentOfTarget
 
 TargetParentOfSource
 
 TransformAvailable
 
 TransformFailure
 

Detailed Description

Author
Koji Terada

Function Documentation

◆ doTransform() [1/8]

template<>
void tf2::doTransform ( const Eigen::Affine3d &  t_in,
Eigen::Affine3d &  t_out,
const geometry_msgs::TransformStamped &  transform 
)
inline

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.

Parameters
t_inThe frame to transform, as a Eigen Affine3d transform.
t_outThe transformed frame, as a Eigen Affine3d transform.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 229 of file tf2_eigen.h.

◆ doTransform() [2/8]

template<>
void tf2::doTransform ( const Eigen::Isometry3d &  t_in,
Eigen::Isometry3d &  t_out,
const geometry_msgs::TransformStamped &  transform 
)
inline

Definition at line 237 of file tf2_eigen.h.

◆ doTransform() [3/8]

template<>
void tf2::doTransform ( const Eigen::Quaterniond &  t_in,
Eigen::Quaterniond &  t_out,
const geometry_msgs::TransformStamped &  transform 
)
inline

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.

Parameters
t_inThe vector to transform, as a Eigen Quaterniond data type.
t_outThe transformed vector, as a Eigen Quaterniond data type.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 279 of file tf2_eigen.h.

◆ doTransform() [4/8]

template<>
void tf2::doTransform ( const Eigen::Vector3d &  t_in,
Eigen::Vector3d &  t_out,
const geometry_msgs::TransformStamped &  transform 
)
inline

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.

Parameters
t_inThe vector to transform, as a Eigen Vector3d data type.
t_outThe transformed vector, as a Eigen Vector3d data type.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 115 of file tf2_eigen.h.

◆ doTransform() [5/8]

template<>
void tf2::doTransform ( const tf2::Stamped< Eigen::Affine3d > &  t_in,
tf2::Stamped< Eigen::Affine3d > &  t_out,
const geometry_msgs::TransformStamped &  transform 
)
inline

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.

Parameters
t_inThe frame to transform, as a timestamped Eigen Affine3d transform.
t_outThe transformed frame, as a timestamped Eigen Affine3d transform.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 452 of file tf2_eigen.h.

◆ doTransform() [6/8]

template<>
void tf2::doTransform ( const tf2::Stamped< Eigen::Isometry3d > &  t_in,
tf2::Stamped< Eigen::Isometry3d > &  t_out,
const geometry_msgs::TransformStamped &  transform 
)
inline

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.

Parameters
t_inThe frame to transform, as a timestamped Eigen Isometry transform.
t_outThe transformed frame, as a timestamped Eigen Isometry transform.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 469 of file tf2_eigen.h.

◆ doTransform() [7/8]

template<>
void tf2::doTransform ( const tf2::Stamped< Eigen::Quaterniond > &  t_in,
tf2::Stamped< Eigen::Quaterniond > &  t_out,
const geometry_msgs::TransformStamped &  transform 
)
inline

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.

Parameters
t_inThe vector to transform, as a timestamped Eigen Quaterniond data type.
t_outThe transformed vector, as a timestamped Eigen Quaterniond data type.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 321 of file tf2_eigen.h.

◆ doTransform() [8/8]

template<>
void tf2::doTransform ( const tf2::Stamped< Eigen::Vector3d > &  t_in,
tf2::Stamped< Eigen::Vector3d > &  t_out,
const geometry_msgs::TransformStamped &  transform 
)
inline

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.

Parameters
t_inThe vector to transform, as a timestamped Eigen Vector3d data type.
t_outThe transformed vector, as a timestamped Eigen Vector3d data type.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 183 of file tf2_eigen.h.

◆ eigenToTransform() [1/2]

geometry_msgs::TransformStamped tf2::eigenToTransform ( const Eigen::Affine3d &  T)
inline

Convert an Eigen Affine3d transform to the equivalent geometry_msgs message type.

Parameters
TThe transform to convert, as an Eigen Affine3d transform.
Returns
The transform converted to a TransformStamped message.

Definition at line 67 of file tf2_eigen.h.

◆ eigenToTransform() [2/2]

geometry_msgs::TransformStamped tf2::eigenToTransform ( const Eigen::Isometry3d &  T)
inline

Convert an Eigen Isometry3d transform to the equivalent geometry_msgs message type.

Parameters
TThe transform to convert, as an Eigen Isometry3d transform.
Returns
The transform converted to a TransformStamped message.

Definition at line 88 of file tf2_eigen.h.

◆ fromMsg() [1/10]

void tf2::fromMsg ( const geometry_msgs::Point &  msg,
Eigen::Vector3d &  out 
)
inline

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.

Parameters
msgThe Point message to convert.
outThe point converted to a Eigen Vector3d.

Definition at line 141 of file tf2_eigen.h.

◆ fromMsg() [2/10]

void tf2::fromMsg ( const geometry_msgs::PointStamped &  msg,
tf2::Stamped< Eigen::Vector3d > &  out 
)
inline

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.

Parameters
msgThe PointStamped message to convert.
outThe point converted to a timestamped Eigen Vector3d.

Definition at line 212 of file tf2_eigen.h.

◆ fromMsg() [3/10]

void tf2::fromMsg ( const geometry_msgs::Pose &  msg,
Eigen::Affine3d &  out 
)
inline

Convert a Pose message transform type to a Eigen Affine3d. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
msgThe Pose message to convert.
outThe pose converted to a Eigen Affine3d.

Definition at line 385 of file tf2_eigen.h.

◆ fromMsg() [4/10]

void tf2::fromMsg ( const geometry_msgs::Pose &  msg,
Eigen::Isometry3d &  out 
)
inline

Convert a Pose message transform type to a Eigen Isometry3d. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
msgThe Pose message to convert.
outThe pose converted to a Eigen Isometry3d.

Definition at line 400 of file tf2_eigen.h.

◆ fromMsg() [5/10]

void tf2::fromMsg ( const geometry_msgs::PoseStamped &  msg,
tf2::Stamped< Eigen::Affine3d > &  out 
)
inline

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.

Parameters
msgThe PoseStamped message to convert.
outThe pose converted to a timestamped Eigen Affine3d.

Definition at line 506 of file tf2_eigen.h.

◆ fromMsg() [6/10]

void tf2::fromMsg ( const geometry_msgs::PoseStamped &  msg,
tf2::Stamped< Eigen::Isometry3d > &  out 
)
inline

Definition at line 514 of file tf2_eigen.h.

◆ fromMsg() [7/10]

void tf2::fromMsg ( const geometry_msgs::Quaternion &  msg,
Eigen::Quaterniond &  out 
)
inline

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.

Parameters
msgThe Quaternion message to convert.
outThe quaternion converted to a Eigen Quaterniond.

Definition at line 264 of file tf2_eigen.h.

◆ fromMsg() [8/10]

void tf2::fromMsg ( const geometry_msgs::QuaternionStamped &  msg,
Stamped< Eigen::Quaterniond > &  out 
)
inline

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.

Parameters
msgThe QuaternionStamped message to convert.
outThe quaternion converted to a timestamped Eigen Quaterniond.

Definition at line 307 of file tf2_eigen.h.

◆ fromMsg() [9/10]

void tf2::fromMsg ( const geometry_msgs::Twist &  msg,
Eigen::Matrix< double, 6, 1 > &  out 
)
inline

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.

Parameters
msgThe Twist message to convert.
outThe twist converted to a Eigen 6x1 Matrix.

Definition at line 432 of file tf2_eigen.h.

◆ fromMsg() [10/10]

void tf2::fromMsg ( const geometry_msgs::Vector3 &  msg,
Eigen::Vector3d &  out 
)
inline

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.

Parameters
msgThe Vector3 message to convert.
outThe vector converted to a Eigen Vector3d.

Definition at line 168 of file tf2_eigen.h.

◆ toMsg() [1/10]

geometry_msgs::Pose tf2::toMsg ( const Eigen::Affine3d &  in)
inline

Convert a Eigen Affine3d transform type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe Eigen Affine3d to convert.
Returns
The Eigen transform converted to a Pose message.

Definition at line 335 of file tf2_eigen.h.

◆ toMsg() [2/10]

geometry_msgs::Pose tf2::toMsg ( const Eigen::Isometry3d &  in)
inline

Convert a Eigen Isometry3d transform type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe Eigen Isometry3d to convert.
Returns
The Eigen transform converted to a Pose message.

Definition at line 360 of file tf2_eigen.h.

◆ toMsg() [3/10]

geometry_msgs::Twist tf2::toMsg ( const Eigen::Matrix< double, 6, 1 > &  in)
inline

Convert a Eigen 6x1 Matrix type to a Twist message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe 6x1 Eigen Matrix to convert.
Returns
The Eigen Matrix converted to a Twist message.

Definition at line 415 of file tf2_eigen.h.

◆ toMsg() [4/10]

geometry_msgs::Quaternion tf2::toMsg ( const Eigen::Quaterniond &  in)
inline

Convert a Eigen Quaterniond type to a Quaternion message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe Eigen Quaterniond to convert.
Returns
The quaternion converted to a Quaterion message.

Definition at line 249 of file tf2_eigen.h.

◆ toMsg() [5/10]

geometry_msgs::Point tf2::toMsg ( const Eigen::Vector3d &  in)
inline

Convert a Eigen Vector3d type to a Point message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe timestamped Eigen Vector3d to convert.
Returns
The vector converted to a Point message.

Definition at line 126 of file tf2_eigen.h.

◆ toMsg() [6/10]

geometry_msgs::Vector3& tf2::toMsg ( const Eigen::Vector3d &  in,
geometry_msgs::Vector3 &  out 
)
inline

Convert an Eigen Vector3d type to a Vector3 message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe Eigen Vector3d to convert.
Returns
The vector converted to a Vector3 message.

Definition at line 154 of file tf2_eigen.h.

◆ toMsg() [7/10]

geometry_msgs::QuaternionStamped tf2::toMsg ( const Stamped< Eigen::Quaterniond > &  in)
inline

Convert a stamped Eigen Quaterniond type to a QuaternionStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe timestamped Eigen Quaterniond to convert.
Returns
The quaternion converted to a QuaternionStamped message.

Definition at line 293 of file tf2_eigen.h.

◆ toMsg() [8/10]

geometry_msgs::PoseStamped tf2::toMsg ( const tf2::Stamped< Eigen::Affine3d > &  in)
inline

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.

Parameters
inThe timestamped Eigen Affine3d to convert.
Returns
The Eigen transform converted to a PoseStamped message.

Definition at line 481 of file tf2_eigen.h.

◆ toMsg() [9/10]

geometry_msgs::PoseStamped tf2::toMsg ( const tf2::Stamped< Eigen::Isometry3d > &  in)
inline

Definition at line 491 of file tf2_eigen.h.

◆ toMsg() [10/10]

geometry_msgs::PointStamped tf2::toMsg ( const tf2::Stamped< Eigen::Vector3d > &  in)
inline

Convert a stamped Eigen Vector3d type to a PointStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe timestamped Eigen Vector3d to convert.
Returns
The vector converted to a PointStamped message.

Definition at line 197 of file tf2_eigen.h.

◆ transformToEigen() [1/2]

Eigen::Isometry3d tf2::transformToEigen ( const geometry_msgs::Transform &  t)
inline

Convert a timestamped transform to the equivalent Eigen data type.

Parameters
tThe transform to convert, as a geometry_msgs Transform message.
Returns
The transform message converted to an Eigen Isometry3d transform.

Definition at line 48 of file tf2_eigen.h.

◆ transformToEigen() [2/2]

Eigen::Isometry3d tf2::transformToEigen ( const geometry_msgs::TransformStamped &  t)
inline

Convert a timestamped transform to the equivalent Eigen data type.

Parameters
tThe transform to convert, as a geometry_msgs TransformedStamped message.
Returns
The transform message converted to an Eigen Isometry3d transform.

Definition at line 58 of file tf2_eigen.h.



tf2_eigen
Author(s): Koji Terada
autogenerated on Sun Feb 4 2024 03:18:14