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

tf2 namespace extension for message conversion overload resolution. More...

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)
 
template<template< typename, std::size_t > class Array, typename Scalar >
Array< Scalar, 36 > & covarianceEigenToRowMajor (const Sophus::Matrix3< Scalar > &in, Array< Scalar, 36 > &out)
 Converts a Sophus (ie. Eigen) 3x3 covariance matrix to a 6x6 row-major array. More...
 
template<template< typename, std::size_t > class Array, typename Scalar >
Sophus::Matrix3< Scalar > & covarianceRowMajorToEigen (const Array< Scalar, 36 > &in, Sophus::Matrix3< Scalar > &out)
 Converts a 6x6 row-major array to an Eigen 3x3 covariance matrix. More...
 
TF2SIMD_FORCE_INLINE tf2Scalar dot (const Quaternion &q1, const Quaternion &q2)
 
void doTransform (const Eigen::Affine3d &t_in, Eigen::Affine3d &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const Eigen::Isometry3d &t_in, Eigen::Isometry3d &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const Eigen::Quaterniond &t_in, Eigen::Quaterniond &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const Eigen::Vector3d &t_in, Eigen::Vector3d &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::Point &t_in, geometry_msgs::Point &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::PointStamped &t_in, geometry_msgs::PointStamped &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::Pose &t_in, geometry_msgs::Pose &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::PoseStamped &t_in, geometry_msgs::PoseStamped &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::PoseWithCovarianceStamped &t_in, geometry_msgs::PoseWithCovarianceStamped &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::Quaternion &t_in, geometry_msgs::Quaternion &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::QuaternionStamped &t_in, geometry_msgs::QuaternionStamped &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::TransformStamped &t_in, geometry_msgs::TransformStamped &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::Vector3 &t_in, geometry_msgs::Vector3 &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::Vector3Stamped &t_in, geometry_msgs::Vector3Stamped &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::Wrench &t_in, geometry_msgs::Wrench &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const geometry_msgs::WrenchStamped &t_in, geometry_msgs::WrenchStamped &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const tf2::Stamped< Eigen::Affine3d > &t_in, tf2::Stamped< Eigen::Affine3d > &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const tf2::Stamped< Eigen::Isometry3d > &t_in, tf2::Stamped< Eigen::Isometry3d > &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const tf2::Stamped< Eigen::Quaterniond > &t_in, tf2::Stamped< Eigen::Quaterniond > &t_out, const geometry_msgs::TransformStamped &transform)
 
void doTransform (const tf2::Stamped< Eigen::Vector3d > &t_in, tf2::Stamped< Eigen::Vector3d > &t_out, const geometry_msgs::TransformStamped &transform)
 
geometry_msgs::TransformStamped eigenToTransform (const Eigen::Affine3d &T)
 
geometry_msgs::TransformStamped eigenToTransform (const Eigen::Isometry3d &T)
 
void fromMsg (const A &, B &b)
 
template<class Scalar >
void fromMsg (const beluga_ros::msg::Pose &msg, Sophus::SE2< Scalar > &out)
 Converts a Pose message type to a Sophus SE2 type. More...
 
template<class Scalar >
void fromMsg (const beluga_ros::msg::Pose &msg, Sophus::SE3< Scalar > &out)
 Converts a Pose message type to a Sophus SE3 type. More...
 
template<class Scalar >
void fromMsg (const beluga_ros::msg::Transform &msg, Sophus::SE2< Scalar > &out)
 Converts a Transform message type to a Sophus SE2 type. More...
 
template<class Scalar >
void fromMsg (const beluga_ros::msg::Transform &msg, Sophus::SE3< Scalar > &out)
 Converts a Transform message type to a Sophus SE3 type. More...
 
void fromMsg (const geometry_msgs::Point &in, tf2::Vector3 &out)
 
void fromMsg (const geometry_msgs::Point &msg, Eigen::Vector3d &out)
 
void fromMsg (const geometry_msgs::PointStamped &msg, geometry_msgs::PointStamped &out)
 
void fromMsg (const geometry_msgs::PointStamped &msg, tf2::Stamped< Eigen::Vector3d > &out)
 
void fromMsg (const geometry_msgs::PointStamped &msg, tf2::Stamped< tf2::Vector3 > &out)
 
void fromMsg (const geometry_msgs::Pose &in, tf2::Transform &out)
 
void fromMsg (const geometry_msgs::Pose &msg, Eigen::Affine3d &out)
 
void fromMsg (const geometry_msgs::Pose &msg, Eigen::Isometry3d &out)
 
void fromMsg (const geometry_msgs::PoseStamped &msg, geometry_msgs::PoseStamped &out)
 
void fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< Eigen::Affine3d > &out)
 
void fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< Eigen::Isometry3d > &out)
 
void fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< tf2::Transform > &out)
 
void fromMsg (const geometry_msgs::PoseWithCovarianceStamped &msg, geometry_msgs::PoseWithCovarianceStamped &out)
 
void fromMsg (const geometry_msgs::PoseWithCovarianceStamped &msg, tf2::Stamped< tf2::Transform > &out)
 
void fromMsg (const geometry_msgs::Quaternion &in, tf2::Quaternion &out)
 
void fromMsg (const geometry_msgs::Quaternion &msg, Eigen::Quaterniond &out)
 
void fromMsg (const geometry_msgs::QuaternionStamped &in, tf2::Stamped< tf2::Quaternion > &out)
 
void fromMsg (const geometry_msgs::QuaternionStamped &msg, geometry_msgs::QuaternionStamped &out)
 
void fromMsg (const geometry_msgs::QuaternionStamped &msg, Stamped< Eigen::Quaterniond > &out)
 
void fromMsg (const geometry_msgs::Transform &in, tf2::Transform &out)
 
void fromMsg (const geometry_msgs::TransformStamped &msg, geometry_msgs::TransformStamped &out)
 
void fromMsg (const geometry_msgs::TransformStamped &msg, tf2::Stamped< tf2::Transform > &out)
 
void fromMsg (const geometry_msgs::Twist &msg, Eigen::Matrix< double, 6, 1 > &out)
 
void fromMsg (const geometry_msgs::Vector3 &in, tf2::Vector3 &out)
 
void fromMsg (const geometry_msgs::Vector3 &msg, Eigen::Vector3d &out)
 
void fromMsg (const geometry_msgs::Vector3Stamped &msg, geometry_msgs::Vector3Stamped &out)
 
void fromMsg (const geometry_msgs::Vector3Stamped &msg, tf2::Stamped< tf2::Vector3 > &out)
 
void fromMsg (const geometry_msgs::WrenchStamped &msg, geometry_msgs::WrenchStamped &out)
 
void fromMsg (const geometry_msgs::WrenchStamped &msg, tf2::Stamped< std::array< tf2::Vector3, 2 >> &out)
 
void getEulerYPR (const A &a, double &yaw, double &pitch, double &roll)
 
const std::string & getFrameId (const geometry_msgs::PointStamped &t)
 
const std::string & getFrameId (const geometry_msgs::PoseStamped &t)
 
const std::string & getFrameId (const geometry_msgs::PoseWithCovarianceStamped &t)
 
const std::string & getFrameId (const geometry_msgs::QuaternionStamped &t)
 
const std::string & getFrameId (const geometry_msgs::TransformStamped &t)
 
const std::string & getFrameId (const geometry_msgs::Vector3Stamped &t)
 
const std::string & getFrameId (const geometry_msgs::WrenchStamped &t)
 
const std::string & getFrameId (const T &t)
 
const std::string & getFrameId (const tf2::Stamped< P > &t)
 
const ros::TimegetTimestamp (const geometry_msgs::PointStamped &t)
 
const ros::TimegetTimestamp (const geometry_msgs::PoseStamped &t)
 
const ros::TimegetTimestamp (const geometry_msgs::PoseWithCovarianceStamped &t)
 
const ros::TimegetTimestamp (const geometry_msgs::QuaternionStamped &t)
 
const ros::TimegetTimestamp (const geometry_msgs::TransformStamped &t)
 
const ros::TimegetTimestamp (const geometry_msgs::Vector3Stamped &t)
 
const ros::TimegetTimestamp (const geometry_msgs::WrenchStamped &t)
 
const ros::TimegetTimestamp (const T &t)
 
const ros::TimegetTimestamp (const tf2::Stamped< P > &t)
 
getTransformIdentity ()
 
double getYaw (const A &a)
 
ROS_DEPRECATED KDL::Frame gmTransformToKDL (const geometry_msgs::TransformStamped &t)
 
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)
 
geometry_msgs::Pose toMsg (const Eigen::Isometry3d &in)
 
geometry_msgs::Twist toMsg (const Eigen::Matrix< double, 6, 1 > &in)
 
template<class Scalar >
beluga_ros::msg::Point toMsg (const Eigen::Matrix< Scalar, 2, 1 > &in)
 Converts an Eigen Vector2 type to a Point message. More...
 
geometry_msgs::Quaternion toMsg (const Eigen::Quaterniond &in)
 
geometry_msgs::Point toMsg (const Eigen::Vector3d &in)
 
geometry_msgs::Vector3toMsg (const Eigen::Vector3d &in, geometry_msgs::Vector3 &out)
 
geometry_msgs::PointStamped toMsg (const geometry_msgs::PointStamped &in)
 
geometry_msgs::PoseStamped toMsg (const geometry_msgs::PoseStamped &in)
 
geometry_msgs::PoseWithCovarianceStamped toMsg (const geometry_msgs::PoseWithCovarianceStamped &in)
 
geometry_msgs::QuaternionStamped toMsg (const geometry_msgs::QuaternionStamped &in)
 
geometry_msgs::TransformStamped toMsg (const geometry_msgs::TransformStamped &in)
 
geometry_msgs::Vector3Stamped toMsg (const geometry_msgs::Vector3Stamped &in)
 
geometry_msgs::WrenchStamped toMsg (const geometry_msgs::WrenchStamped &in)
 
template<class Scalar >
beluga_ros::msg::Transform toMsg (const Sophus::SE2< Scalar > &in)
 Converts a Sophus SE2 type to a Transform message. More...
 
template<class Scalar >
beluga_ros::msg::Pose & toMsg (const Sophus::SE2< Scalar > &in, beluga_ros::msg::Pose &out)
 Converts a Sophus SE2 type to a Pose message. More...
 
template<class Scalar >
beluga_ros::msg::Transform toMsg (const Sophus::SE3< Scalar > &in)
 Converts a Sophus SE3 type to a Transform message. More...
 
template<class Scalar >
beluga_ros::msg::Pose & toMsg (const Sophus::SE3< Scalar > &in, beluga_ros::msg::Pose &out)
 Converts a Sophus SE3 type to a Pose message. More...
 
geometry_msgs::QuaternionStamped toMsg (const Stamped< Eigen::Quaterniond > &in)
 
geometry_msgs::Quaternion toMsg (const tf2::Quaternion &in)
 
geometry_msgs::PoseStamped toMsg (const tf2::Stamped< Eigen::Affine3d > &in)
 
geometry_msgs::PoseStamped toMsg (const tf2::Stamped< Eigen::Isometry3d > &in)
 
geometry_msgs::PointStamped toMsg (const tf2::Stamped< Eigen::Vector3d > &in)
 
geometry_msgs::WrenchStamped toMsg (const tf2::Stamped< std::array< tf2::Vector3, 2 >> &in, geometry_msgs::WrenchStamped &out)
 
geometry_msgs::QuaternionStamped toMsg (const tf2::Stamped< tf2::Quaternion > &in)
 
geometry_msgs::TransformStamped toMsg (const tf2::Stamped< tf2::Transform > &in)
 
geometry_msgs::PoseStamped toMsg (const tf2::Stamped< tf2::Transform > &in, geometry_msgs::PoseStamped &out)
 
geometry_msgs::PoseWithCovarianceStamped toMsg (const tf2::Stamped< tf2::Transform > &in, geometry_msgs::PoseWithCovarianceStamped &out)
 
geometry_msgs::Vector3Stamped toMsg (const tf2::Stamped< tf2::Vector3 > &in)
 
geometry_msgs::PointStamped toMsg (const tf2::Stamped< tf2::Vector3 > &in, geometry_msgs::PointStamped &out)
 
geometry_msgs::Transform toMsg (const tf2::Transform &in)
 
geometry_msgs::Pose & toMsg (const tf2::Transform &in, geometry_msgs::Pose &out)
 
geometry_msgs::Vector3 toMsg (const tf2::Vector3 &in)
 
geometry_msgs::Point & toMsg (const tf2::Vector3 &in, geometry_msgs::Point &out)
 
geometry_msgs::PoseWithCovariance::_covariance_type transformCovariance (const geometry_msgs::PoseWithCovariance::_covariance_type &cov_in, const tf2::Transform &transform)
 
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)
 
Eigen::Isometry3d transformToEigen (const geometry_msgs::TransformStamped &t)
 

Variables

 FullPath
 
 Identity
 
static double QUATERNION_NORMALIZATION_TOLERANCE
 
 SourceParentOfTarget
 
 TargetParentOfSource
 
 TransformAvailable
 
 TransformFailure
 

Detailed Description

tf2 namespace extension for message conversion overload resolution.

Function Documentation

◆ covarianceEigenToRowMajor()

template<template< typename, std::size_t > class Array, typename Scalar >
Array<Scalar, 36>& tf2::covarianceEigenToRowMajor ( const Sophus::Matrix3< Scalar > &  in,
Array< Scalar, 36 > &  out 
)
inline

Converts a Sophus (ie. Eigen) 3x3 covariance matrix to a 6x6 row-major array.

Parameters
inA Sophus (ie. Eigen) 3x3 covariance matrix of a 2D pose (x, y, yaw).
outA row-major array of 36 covariance values of a 3D pose.
Returns
a reference to out.

Definition at line 214 of file tf2_sophus.hpp.

◆ covarianceRowMajorToEigen()

template<template< typename, std::size_t > class Array, typename Scalar >
Sophus::Matrix3<Scalar>& tf2::covarianceRowMajorToEigen ( const Array< Scalar, 36 > &  in,
Sophus::Matrix3< Scalar > &  out 
)
inline

Converts a 6x6 row-major array to an Eigen 3x3 covariance matrix.

Parameters
inA row-major array of 36 covariance values of a 3D pose.
outA Sophus (ie. Eigen) 3x3 covariance matrix of a 2D pose (x, y, yaw).
Returns
A Sophus (ie. Eigen) 3x3 covariance matrix of a 2D pose (x, y, yaw).

Definition at line 235 of file tf2_sophus.hpp.

◆ fromMsg() [1/4]

template<class Scalar >
void tf2::fromMsg ( const beluga_ros::msg::Pose &  msg,
Sophus::SE2< Scalar > &  out 
)
inline

Converts a Pose message type to a Sophus SE2 type.

This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe pose message to convert.
outThe pose converted to a Sophus SE2 element.

Definition at line 177 of file tf2_sophus.hpp.

◆ fromMsg() [2/4]

template<class Scalar >
void tf2::fromMsg ( const beluga_ros::msg::Pose &  msg,
Sophus::SE3< Scalar > &  out 
)
inline

Converts a Pose message type to a Sophus SE3 type.

This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe pose message to convert.
outThe pose converted to a Sophus SE3 element.

Definition at line 193 of file tf2_sophus.hpp.

◆ fromMsg() [3/4]

template<class Scalar >
void tf2::fromMsg ( const beluga_ros::msg::Transform &  msg,
Sophus::SE2< Scalar > &  out 
)
inline

Converts a Transform message type to a Sophus SE2 type.

This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe transform message to convert.
outThe transform converted to a Sophus SE2 element.

Definition at line 139 of file tf2_sophus.hpp.

◆ fromMsg() [4/4]

template<class Scalar >
void tf2::fromMsg ( const beluga_ros::msg::Transform &  msg,
Sophus::SE3< Scalar > &  out 
)
inline

Converts a Transform message type to a Sophus SE3 type.

This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe transform message to convert.
outThe transform converted to a Sophus SE3 element.

Definition at line 155 of file tf2_sophus.hpp.

◆ toMsg() [1/5]

template<class Scalar >
beluga_ros::msg::Point tf2::toMsg ( const Eigen::Matrix< Scalar, 2, 1 > &  in)
inline

Converts an Eigen Vector2 type to a Point message.

Parameters
inThe Eigen Vector2 element to convert.
Returns
The converted Point message.

Definition at line 46 of file tf2_eigen.hpp.

◆ toMsg() [2/5]

template<class Scalar >
beluga_ros::msg::Transform tf2::toMsg ( const Sophus::SE2< Scalar > &  in)
inline

Converts a Sophus SE2 type to a Transform message.

This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe Sophus SE2 element to convert.
Returns
The transform converted to a Transform message.

Definition at line 98 of file tf2_sophus.hpp.

◆ toMsg() [3/5]

template<class Scalar >
beluga_ros::msg::Pose& tf2::toMsg ( const Sophus::SE2< Scalar > &  in,
beluga_ros::msg::Pose &  out 
)
inline

Converts a Sophus SE2 type to a Pose message.

The canonical message for an SE2 instance is Transform. If a Pose message is needed, this function must be called directly using tf2::toMsg, not through the tf2::convert customization function.

Parameters
inThe Sophus SE2 element to convert.
outThe pose converted to a Pose message.
Returns
The pose converted to a Pose message.

Definition at line 56 of file tf2_sophus.hpp.

◆ toMsg() [4/5]

template<class Scalar >
beluga_ros::msg::Transform tf2::toMsg ( const Sophus::SE3< Scalar > &  in)
inline

Converts a Sophus SE3 type to a Transform message.

This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe Sophus SE3 element to convert.
Returns
The transform converted to a Transform message.

Definition at line 119 of file tf2_sophus.hpp.

◆ toMsg() [5/5]

template<class Scalar >
beluga_ros::msg::Pose& tf2::toMsg ( const Sophus::SE3< Scalar > &  in,
beluga_ros::msg::Pose &  out 
)
inline

Converts a Sophus SE3 type to a Pose message.

The canonical message for an SE3 instance is Transform. If a Pose message is needed, this function must be called directly using tf2::toMsg, not through the tf2::convert customization function.

Parameters
inThe Sophus SE3 element to convert.
outThe pose converted to a Pose message.
Returns
The pose converted to a Pose message.

Definition at line 79 of file tf2_sophus.hpp.



beluga_ros
Author(s):
autogenerated on Tue Jul 16 2024 03:00:02