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 geometry_msgs::Point &t_in, geometry_msgs::Point &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Point type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::PointStamped &t_in, geometry_msgs::PointStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Point type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::Pose &t_in, geometry_msgs::Pose &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Pose type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::PoseStamped &t_in, geometry_msgs::PoseStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Pose type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::PoseWithCovarianceStamped &t_in, geometry_msgs::PoseWithCovarianceStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs PoseWithCovarianceStamped type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::Quaternion &t_in, geometry_msgs::Quaternion &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Quaternion type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::QuaternionStamped &t_in, geometry_msgs::QuaternionStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Quaternion type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::TransformStamped &t_in, geometry_msgs::TransformStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Transform type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::Vector3 &t_in, geometry_msgs::Vector3 &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::Vector3Stamped &t_in, geometry_msgs::Vector3Stamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::Wrench &t_in, geometry_msgs::Wrench &t_out, const geometry_msgs::TransformStamped &transform)
 
template<>
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 fromMsg (const A &, B &b)
 
void fromMsg (const geometry_msgs::Point &in, tf2::Vector3 &out)
 Convert a Vector3 message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::PointStamped &msg, geometry_msgs::PointStamped &out)
 Trivial "conversion" function for Point message 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< tf2::Vector3 > &out)
 Convert a PointStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::Pose &in, tf2::Transform &out)
 Convert a geometry_msgs Pose message to an equivalent tf2 Transform type. More...
 
void fromMsg (const geometry_msgs::PoseStamped &msg, geometry_msgs::PoseStamped &out)
 Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< tf2::Transform > &out)
 Convert a PoseStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::PoseWithCovarianceStamped &msg, geometry_msgs::PoseWithCovarianceStamped &out)
 Trivial "conversion" function for PoseWithCovarianceStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::PoseWithCovarianceStamped &msg, tf2::Stamped< tf2::Transform > &out)
 Convert a PoseWithCovarianceStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::Quaternion &in, tf2::Quaternion &out)
 Convert a Quaternion message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::QuaternionStamped &in, tf2::Stamped< tf2::Quaternion > &out)
 Convert a QuaternionStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::QuaternionStamped &msg, geometry_msgs::QuaternionStamped &out)
 Trivial "conversion" function for Quaternion message type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::Transform &in, tf2::Transform &out)
 Convert a Transform message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::TransformStamped &msg, geometry_msgs::TransformStamped &out)
 Trivial "conversion" function for TransformStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::TransformStamped &msg, tf2::Stamped< tf2::Transform > &out)
 Convert a TransformStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::Vector3 &in, tf2::Vector3 &out)
 Convert a Vector3 message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::Vector3Stamped &msg, geometry_msgs::Vector3Stamped &out)
 Trivial "conversion" function for Vector3 message type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::Vector3Stamped &msg, tf2::Stamped< tf2::Vector3 > &out)
 Convert a Vector3Stamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
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)
 
template<>
const std::string & getFrameId (const geometry_msgs::PointStamped &t)
 Extract a frame ID from the header of a Point message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & getFrameId (const geometry_msgs::PoseStamped &t)
 Extract a frame ID from the header of a Pose message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & getFrameId (const geometry_msgs::PoseWithCovarianceStamped &t)
 Extract a frame ID from the header of a PoseWithCovarianceStamped message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & getFrameId (const geometry_msgs::QuaternionStamped &t)
 Extract a frame ID from the header of a Quaternion message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & getFrameId (const geometry_msgs::TransformStamped &t)
 Extract a frame ID from the header of a Transform message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & getFrameId (const geometry_msgs::Vector3Stamped &t)
 Extract a frame ID from the header of a Vector message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
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)
 
template<>
const ros::TimegetTimestamp (const geometry_msgs::PointStamped &t)
 Extract a timestamp from the header of a Point message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::TimegetTimestamp (const geometry_msgs::PoseStamped &t)
 Extract a timestamp from the header of a Pose message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::TimegetTimestamp (const geometry_msgs::PoseWithCovarianceStamped &t)
 Extract a timestamp from the header of a PoseWithCovarianceStamped message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::TimegetTimestamp (const geometry_msgs::QuaternionStamped &t)
 Extract a timestamp from the header of a Quaternion message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::TimegetTimestamp (const geometry_msgs::TransformStamped &t)
 Extract a timestamp from the header of a Transform message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::TimegetTimestamp (const geometry_msgs::Vector3Stamped &t)
 Extract a timestamp from the header of a Vector message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
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)
 Convert a TransformStamped message to a KDL frame. More...
 
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::PointStamped toMsg (const geometry_msgs::PointStamped &in)
 Trivial "conversion" function for Point message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseStamped toMsg (const geometry_msgs::PoseStamped &in)
 Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseWithCovarianceStamped toMsg (const geometry_msgs::PoseWithCovarianceStamped &in)
 Trivial "conversion" function for PoseWithCovarianceStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::QuaternionStamped toMsg (const geometry_msgs::QuaternionStamped &in)
 Trivial "conversion" function for Quaternion message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::TransformStamped toMsg (const geometry_msgs::TransformStamped &in)
 Trivial "conversion" function for Transform message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Vector3Stamped toMsg (const geometry_msgs::Vector3Stamped &in)
 Trivial "conversion" function for Vector3 message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::WrenchStamped toMsg (const geometry_msgs::WrenchStamped &in)
 
geometry_msgs::Quaternion toMsg (const tf2::Quaternion &in)
 Convert a tf2 Quaternion type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
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)
 Convert as stamped tf2 Quaternion type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::TransformStamped toMsg (const tf2::Stamped< tf2::Transform > &in)
 Convert as stamped tf2 Transform type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseStamped toMsg (const tf2::Stamped< tf2::Transform > &in, geometry_msgs::PoseStamped &out)
 Convert as stamped tf2 Pose type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseWithCovarianceStamped toMsg (const tf2::Stamped< tf2::Transform > &in, geometry_msgs::PoseWithCovarianceStamped &out)
 Convert as stamped tf2 PoseWithCovarianceStamped type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Vector3Stamped toMsg (const tf2::Stamped< tf2::Vector3 > &in)
 Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PointStamped toMsg (const tf2::Stamped< tf2::Vector3 > &in, geometry_msgs::PointStamped &out)
 Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Transform toMsg (const tf2::Transform &in)
 Convert a tf2 Transform type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Pose & toMsg (const tf2::Transform &in, geometry_msgs::Pose &out)
 Convert a tf2 Transform type to an equivalent geometry_msgs Pose message. More...
 
geometry_msgs::Vector3 toMsg (const tf2::Vector3 &in)
 Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Point & toMsg (const tf2::Vector3 &in, geometry_msgs::Point &out)
 Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseWithCovariance::_covariance_type transformCovariance (const geometry_msgs::PoseWithCovariance::_covariance_type &cov_in, const tf2::Transform &transform)
 Transform the covariance matrix of a PoseWithCovarianceStamped message to a new frame. 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)
 

Variables

 FullPath
 
 Identity
 
static double QUATERNION_NORMALIZATION_TOLERANCE
 
 SourceParentOfTarget
 
 TargetParentOfSource
 
 TransformAvailable
 
 TransformFailure
 

Detailed Description

Author
Wim Meeussen

Function Documentation

◆ doTransform() [1/12]

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

Apply a geometry_msgs TransformStamped to an geometry_msgs Point type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe point to transform, as a Point3 message.
t_outThe transformed point, as a Point3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 721 of file tf2_geometry_msgs.h.

◆ doTransform() [2/12]

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

Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Point type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe point to transform, as a timestamped Point3 message.
t_outThe transformed point, as a timestamped Point3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 739 of file tf2_geometry_msgs.h.

◆ doTransform() [3/12]

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

Apply a geometry_msgs TransformStamped to an geometry_msgs Pose type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe pose to transform, as a Pose3 message.
t_outThe transformed pose, as a Pose3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 788 of file tf2_geometry_msgs.h.

◆ doTransform() [4/12]

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

Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Pose type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe pose to transform, as a timestamped Pose3 message.
t_outThe transformed pose, as a timestamped Pose3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 809 of file tf2_geometry_msgs.h.

◆ doTransform() [5/12]

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

Apply a geometry_msgs TransformStamped to an geometry_msgs PoseWithCovarianceStamped type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe pose to transform, as a timestamped PoseWithCovarianceStamped message.
t_outThe transformed pose, as a timestamped PoseWithCovarianceStamped message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 912 of file tf2_geometry_msgs.h.

◆ doTransform() [6/12]

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

Apply a geometry_msgs TransformStamped to an geometry_msgs Quaternion type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe quaternion to transform, as a Quaternion3 message.
t_outThe transformed quaternion, as a Quaternion3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 754 of file tf2_geometry_msgs.h.

◆ doTransform() [7/12]

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

Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Quaternion type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe quaternion to transform, as a timestamped Quaternion3 message.
t_outThe transformed quaternion, as a timestamped Quaternion3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 772 of file tf2_geometry_msgs.h.

◆ doTransform() [8/12]

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

Apply a geometry_msgs TransformStamped to an geometry_msgs Transform type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe frame to transform, as a timestamped Transform3 message.
t_outThe frame transform, as a timestamped Transform3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 937 of file tf2_geometry_msgs.h.

◆ doTransform() [9/12]

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

Apply a geometry_msgs TransformStamped to an geometry_msgs Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe vector to transform, as a Vector3 message.
t_outThe transformed vector, as a Vector3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 959 of file tf2_geometry_msgs.h.

◆ doTransform() [10/12]

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

Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe vector to transform, as a timestamped Vector3 message.
t_outThe transformed vector, as a timestamped Vector3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 977 of file tf2_geometry_msgs.h.

◆ doTransform() [11/12]

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

Definition at line 1039 of file tf2_geometry_msgs.h.

◆ doTransform() [12/12]

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

Definition at line 1055 of file tf2_geometry_msgs.h.

◆ fromMsg() [1/19]

void tf2::fromMsg ( const geometry_msgs::Point &  in,
tf2::Vector3 &  out 
)
inline

Convert a Vector3 message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
inA Vector3 message type.
outThe Vector3 converted to a tf2 type.

Definition at line 205 of file tf2_geometry_msgs.h.

◆ fromMsg() [2/19]

void tf2::fromMsg ( const geometry_msgs::PointStamped &  msg,
geometry_msgs::PointStamped &  out 
)
inline

Trivial "conversion" function for Point message type. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgA PointStamped message.
outThe input argument.

Definition at line 252 of file tf2_geometry_msgs.h.

◆ fromMsg() [3/19]

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

Convert a PointStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgA PointStamped message.
outThe PointStamped converted to the equivalent tf2 type.

Definition at line 279 of file tf2_geometry_msgs.h.

◆ fromMsg() [4/19]

void tf2::fromMsg ( const geometry_msgs::Pose &  in,
tf2::Transform out 
)
inline

Convert a geometry_msgs Pose message to an equivalent tf2 Transform type.

Parameters
inA Pose message.
outThe Pose converted to a tf2 Transform type.

Definition at line 445 of file tf2_geometry_msgs.h.

◆ fromMsg() [5/19]

void tf2::fromMsg ( const geometry_msgs::PoseStamped &  msg,
geometry_msgs::PoseStamped &  out 
)
inline

Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
msgA PoseStamped message.
outThe input argument.

Definition at line 493 of file tf2_geometry_msgs.h.

◆ fromMsg() [6/19]

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

Convert a PoseStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgA PoseStamped message.
outThe PoseStamped converted to the equivalent tf2 type.

Definition at line 519 of file tf2_geometry_msgs.h.

◆ fromMsg() [7/19]

void tf2::fromMsg ( const geometry_msgs::PoseWithCovarianceStamped &  msg,
geometry_msgs::PoseWithCovarianceStamped &  out 
)
inline

Trivial "conversion" function for PoseWithCovarianceStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
msgA PoseWithCovarianceStamped message.
outThe input argument.

Definition at line 567 of file tf2_geometry_msgs.h.

◆ fromMsg() [8/19]

void tf2::fromMsg ( const geometry_msgs::PoseWithCovarianceStamped &  msg,
tf2::Stamped< tf2::Transform > &  out 
)
inline

Convert a PoseWithCovarianceStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgA PoseWithCovarianceStamped message.
outThe PoseWithCovarianceStamped converted to the equivalent tf2 type.

Definition at line 593 of file tf2_geometry_msgs.h.

◆ fromMsg() [9/19]

void tf2::fromMsg ( const geometry_msgs::Quaternion &  in,
tf2::Quaternion out 
)
inline

Convert a Quaternion message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
inA Quaternion message type.
outThe Quaternion converted to a tf2 type.

Definition at line 313 of file tf2_geometry_msgs.h.

◆ fromMsg() [10/19]

void tf2::fromMsg ( const geometry_msgs::QuaternionStamped &  in,
tf2::Stamped< tf2::Quaternion > &  out 
)
inline

Convert a QuaternionStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
inA QuaternionStamped message type.
outThe QuaternionStamped converted to the equivalent tf2 type.

Definition at line 403 of file tf2_geometry_msgs.h.

◆ fromMsg() [11/19]

void tf2::fromMsg ( const geometry_msgs::QuaternionStamped &  msg,
geometry_msgs::QuaternionStamped &  out 
)
inline

Trivial "conversion" function for Quaternion message type. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgA QuaternionStamped message.
outThe input argument.

Definition at line 361 of file tf2_geometry_msgs.h.

◆ fromMsg() [12/19]

void tf2::fromMsg ( const geometry_msgs::Transform &  in,
tf2::Transform out 
)
inline

Convert a Transform message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inA Transform message type.
outThe Transform converted to a tf2 type.

Definition at line 626 of file tf2_geometry_msgs.h.

◆ fromMsg() [13/19]

void tf2::fromMsg ( const geometry_msgs::TransformStamped &  msg,
geometry_msgs::TransformStamped &  out 
)
inline

Trivial "conversion" function for TransformStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
msgA TransformStamped message.
outThe input argument.

Definition at line 676 of file tf2_geometry_msgs.h.

◆ fromMsg() [14/19]

void tf2::fromMsg ( const geometry_msgs::TransformStamped &  msg,
tf2::Stamped< tf2::Transform > &  out 
)
inline

Convert a TransformStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgA TransformStamped message.
outThe TransformStamped converted to the equivalent tf2 type.

Definition at line 704 of file tf2_geometry_msgs.h.

◆ fromMsg() [15/19]

void tf2::fromMsg ( const geometry_msgs::Vector3 &  in,
tf2::Vector3 &  out 
)
inline

Convert a Vector3 message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
inA Vector3 message type.
outThe Vector3 converted to a tf2 type.

Definition at line 97 of file tf2_geometry_msgs.h.

◆ fromMsg() [16/19]

void tf2::fromMsg ( const geometry_msgs::Vector3Stamped &  msg,
geometry_msgs::Vector3Stamped &  out 
)
inline

Trivial "conversion" function for Vector3 message type. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgA Vector3Stamped message.
outThe input argument.

Definition at line 145 of file tf2_geometry_msgs.h.

◆ fromMsg() [17/19]

void tf2::fromMsg ( const geometry_msgs::Vector3Stamped &  msg,
tf2::Stamped< tf2::Vector3 > &  out 
)
inline

Convert a Vector3Stamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgA Vector3Stamped message.
outThe Vector3Stamped converted to the equivalent tf2 type.

Definition at line 173 of file tf2_geometry_msgs.h.

◆ fromMsg() [18/19]

void tf2::fromMsg ( const geometry_msgs::WrenchStamped &  msg,
geometry_msgs::WrenchStamped &  out 
)
inline

Definition at line 1005 of file tf2_geometry_msgs.h.

◆ fromMsg() [19/19]

void tf2::fromMsg ( const geometry_msgs::WrenchStamped &  msg,
tf2::Stamped< std::array< tf2::Vector3, 2 >> &  out 
)
inline

Definition at line 1023 of file tf2_geometry_msgs.h.

◆ getFrameId() [1/7]

template<>
const std::string& tf2::getFrameId ( const geometry_msgs::PointStamped &  t)
inline

Extract a frame ID from the header of a Point message. This function is a specialization of the getFrameId template defined in tf2/convert.h.

Parameters
tPointStamped message to extract the frame ID from.
Returns
A string containing the frame ID of the message. The lifetime of the returned reference is bound to the lifetime of the argument.

Definition at line 233 of file tf2_geometry_msgs.h.

◆ getFrameId() [2/7]

template<>
const std::string& tf2::getFrameId ( const geometry_msgs::PoseStamped &  t)
inline

Extract a frame ID from the header of a Pose message. This function is a specialization of the getFrameId template defined in tf2/convert.h.

Parameters
tPoseStamped message to extract the frame ID from.
Returns
A string containing the frame ID of the message.

Definition at line 474 of file tf2_geometry_msgs.h.

◆ getFrameId() [3/7]

template<>
const std::string& tf2::getFrameId ( const geometry_msgs::PoseWithCovarianceStamped &  t)
inline

Extract a frame ID from the header of a PoseWithCovarianceStamped message. This function is a specialization of the getFrameId template defined in tf2/convert.h.

Parameters
tPoseWithCovarianceStamped message to extract the frame ID from.
Returns
A string containing the frame ID of the message.

Definition at line 548 of file tf2_geometry_msgs.h.

◆ getFrameId() [4/7]

template<>
const std::string& tf2::getFrameId ( const geometry_msgs::QuaternionStamped &  t)
inline

Extract a frame ID from the header of a Quaternion message. This function is a specialization of the getFrameId template defined in tf2/convert.h.

Parameters
tQuaternionStamped message to extract the frame ID from.
Returns
A string containing the frame ID of the message. The lifetime of the returned reference is bound to the lifetime of the argument.

Definition at line 342 of file tf2_geometry_msgs.h.

◆ getFrameId() [5/7]

template<>
const std::string& tf2::getFrameId ( const geometry_msgs::TransformStamped &  t)
inline

Extract a frame ID from the header of a Transform message. This function is a specialization of the getFrameId template defined in tf2/convert.h.

Parameters
tTransformStamped message to extract the frame ID from.
Returns
A string containing the frame ID of the message.

Definition at line 658 of file tf2_geometry_msgs.h.

◆ getFrameId() [6/7]

template<>
const std::string& tf2::getFrameId ( const geometry_msgs::Vector3Stamped &  t)
inline

Extract a frame ID from the header of a Vector message. This function is a specialization of the getFrameId template defined in tf2/convert.h.

Parameters
tVectorStamped message to extract the frame ID from.
Returns
A string containing the frame ID of the message. The lifetime of the returned reference is bound to the lifetime of the argument.

Definition at line 125 of file tf2_geometry_msgs.h.

◆ getFrameId() [7/7]

template<>
const std::string& tf2::getFrameId ( const geometry_msgs::WrenchStamped &  t)
inline

Definition at line 995 of file tf2_geometry_msgs.h.

◆ getTimestamp() [1/7]

template<>
const ros::Time& tf2::getTimestamp ( const geometry_msgs::PointStamped &  t)
inline

Extract a timestamp from the header of a Point message. This function is a specialization of the getTimestamp template defined in tf2/convert.h.

PointStamped

Parameters
tPointStamped message to extract the timestamp from.
Returns
The timestamp of the message. The lifetime of the returned reference is bound to the lifetime of the argument.

Definition at line 223 of file tf2_geometry_msgs.h.

◆ getTimestamp() [2/7]

template<>
const ros::Time& tf2::getTimestamp ( const geometry_msgs::PoseStamped &  t)
inline

Extract a timestamp from the header of a Pose message. This function is a specialization of the getTimestamp template defined in tf2/convert.h.

PoseStamped

Parameters
tPoseStamped message to extract the timestamp from.
Returns
The timestamp of the message.

Definition at line 465 of file tf2_geometry_msgs.h.

◆ getTimestamp() [3/7]

template<>
const ros::Time& tf2::getTimestamp ( const geometry_msgs::PoseWithCovarianceStamped &  t)
inline

Extract a timestamp from the header of a PoseWithCovarianceStamped message. This function is a specialization of the getTimestamp template defined in tf2/convert.h.

PoseWithCovarianceStamped

Parameters
tPoseWithCovarianceStamped message to extract the timestamp from.
Returns
The timestamp of the message.

Definition at line 539 of file tf2_geometry_msgs.h.

◆ getTimestamp() [4/7]

template<>
const ros::Time& tf2::getTimestamp ( const geometry_msgs::QuaternionStamped &  t)
inline

Extract a timestamp from the header of a Quaternion message. This function is a specialization of the getTimestamp template defined in tf2/convert.h.

QuaternionStamped

Parameters
tQuaternionStamped message to extract the timestamp from.
Returns
The timestamp of the message. The lifetime of the returned reference is bound to the lifetime of the argument.

Definition at line 332 of file tf2_geometry_msgs.h.

◆ getTimestamp() [5/7]

template<>
const ros::Time& tf2::getTimestamp ( const geometry_msgs::TransformStamped &  t)
inline

Extract a timestamp from the header of a Transform message. This function is a specialization of the getTimestamp template defined in tf2/convert.h.

TransformStamped

Parameters
tTransformStamped message to extract the timestamp from.
Returns
The timestamp of the message.

Definition at line 649 of file tf2_geometry_msgs.h.

◆ getTimestamp() [6/7]

template<>
const ros::Time& tf2::getTimestamp ( const geometry_msgs::Vector3Stamped &  t)
inline

Extract a timestamp from the header of a Vector message. This function is a specialization of the getTimestamp template defined in tf2/convert.h.

Vector3Stamped

Parameters
tVectorStamped message to extract the timestamp from.
Returns
The timestamp of the message. The lifetime of the returned reference is bound to the lifetime of the argument.

Definition at line 115 of file tf2_geometry_msgs.h.

◆ getTimestamp() [7/7]

template<>
const ros::Time& tf2::getTimestamp ( const geometry_msgs::WrenchStamped &  t)
inline

Definition at line 990 of file tf2_geometry_msgs.h.

◆ gmTransformToKDL()

KDL::Frame tf2::gmTransformToKDL ( const geometry_msgs::TransformStamped &  t)
inline

Convert a TransformStamped message to a KDL frame.

Parameters
tTransformStamped message to convert.
Returns
The converted KDL Frame.
Deprecated:

Definition at line 64 of file tf2_geometry_msgs.h.

◆ toMsg() [1/19]

geometry_msgs::PointStamped tf2::toMsg ( const geometry_msgs::PointStamped &  in)
inline

Trivial "conversion" function for Point message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inA PointStamped message.
Returns
The input argument.

Definition at line 241 of file tf2_geometry_msgs.h.

◆ toMsg() [2/19]

geometry_msgs::PoseStamped tf2::toMsg ( const geometry_msgs::PoseStamped &  in)
inline

Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inA PoseStamped message.
Returns
The input argument.

Definition at line 482 of file tf2_geometry_msgs.h.

◆ toMsg() [3/19]

geometry_msgs::PoseWithCovarianceStamped tf2::toMsg ( const geometry_msgs::PoseWithCovarianceStamped &  in)
inline

Trivial "conversion" function for PoseWithCovarianceStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inA PoseWithCovarianceStamped message.
Returns
The input argument.

Definition at line 556 of file tf2_geometry_msgs.h.

◆ toMsg() [4/19]

geometry_msgs::QuaternionStamped tf2::toMsg ( const geometry_msgs::QuaternionStamped &  in)
inline

Trivial "conversion" function for Quaternion message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inA QuaternionStamped message.
Returns
The input argument.

Definition at line 350 of file tf2_geometry_msgs.h.

◆ toMsg() [5/19]

geometry_msgs::TransformStamped tf2::toMsg ( const geometry_msgs::TransformStamped &  in)
inline

Trivial "conversion" function for Transform message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inA TransformStamped message.
Returns
The input argument.

Definition at line 666 of file tf2_geometry_msgs.h.

◆ toMsg() [6/19]

geometry_msgs::Vector3Stamped tf2::toMsg ( const geometry_msgs::Vector3Stamped &  in)
inline

Trivial "conversion" function for Vector3 message type. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inA Vector3Stamped message.
Returns
The input argument.

Definition at line 134 of file tf2_geometry_msgs.h.

◆ toMsg() [7/19]

geometry_msgs::WrenchStamped tf2::toMsg ( const geometry_msgs::WrenchStamped &  in)
inline

Definition at line 999 of file tf2_geometry_msgs.h.

◆ toMsg() [8/19]

geometry_msgs::Quaternion tf2::toMsg ( const tf2::Quaternion in)
inline

Convert a tf2 Quaternion type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Quaternion

Parameters
inA tf2 Quaternion object.
Returns
The Quaternion converted to a geometry_msgs message type.

Definition at line 297 of file tf2_geometry_msgs.h.

◆ toMsg() [9/19]

geometry_msgs::WrenchStamped tf2::toMsg ( const tf2::Stamped< std::array< tf2::Vector3, 2 >> &  in,
geometry_msgs::WrenchStamped &  out 
)
inline

Definition at line 1012 of file tf2_geometry_msgs.h.

◆ toMsg() [10/19]

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

Convert as stamped tf2 Quaternion type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inAn instance of the tf2::Quaternion specialization of the tf2::Stamped template.
Returns
The QuaternionStamped converted to a geometry_msgs QuaternionStamped message type.

Definition at line 372 of file tf2_geometry_msgs.h.

◆ toMsg() [11/19]

geometry_msgs::TransformStamped tf2::toMsg ( const tf2::Stamped< tf2::Transform > &  in)
inline

Convert as stamped tf2 Transform type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inAn instance of the tf2::Transform specialization of the tf2::Stamped template.
Returns
The tf2::Stamped<tf2::Transform> converted to a geometry_msgs TransformStamped message type.

Definition at line 687 of file tf2_geometry_msgs.h.

◆ toMsg() [12/19]

geometry_msgs::PoseStamped tf2::toMsg ( const tf2::Stamped< tf2::Transform > &  in,
geometry_msgs::PoseStamped &  out 
)
inline

Convert as stamped tf2 Pose type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inAn instance of the tf2::Pose specialization of the tf2::Stamped template.
Returns
The PoseStamped converted to a geometry_msgs PoseStamped message type.

Definition at line 504 of file tf2_geometry_msgs.h.

◆ toMsg() [13/19]

geometry_msgs::PoseWithCovarianceStamped tf2::toMsg ( const tf2::Stamped< tf2::Transform > &  in,
geometry_msgs::PoseWithCovarianceStamped &  out 
)
inline

Convert as stamped tf2 PoseWithCovarianceStamped type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inAn instance of the tf2::Pose specialization of the tf2::Stamped template.
Returns
The PoseWithCovarianceStamped converted to a geometry_msgs PoseWithCovarianceStamped message type.

Definition at line 578 of file tf2_geometry_msgs.h.

◆ toMsg() [14/19]

geometry_msgs::Vector3Stamped tf2::toMsg ( const tf2::Stamped< tf2::Vector3 > &  in)
inline

Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inAn instance of the tf2::Vector3 specialization of the tf2::Stamped template.
Returns
The Vector3Stamped converted to a geometry_msgs Vector3Stamped message type.

Definition at line 156 of file tf2_geometry_msgs.h.

◆ toMsg() [15/19]

geometry_msgs::PointStamped tf2::toMsg ( const tf2::Stamped< tf2::Vector3 > &  in,
geometry_msgs::PointStamped &  out 
)
inline

Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inAn instance of the tf2::Vector3 specialization of the tf2::Stamped template.
Returns
The Vector3Stamped converted to a geometry_msgs PointStamped message type.

Definition at line 263 of file tf2_geometry_msgs.h.

◆ toMsg() [16/19]

geometry_msgs::Transform tf2::toMsg ( const tf2::Transform in)
inline

Convert a tf2 Transform type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Transform

Parameters
inA tf2 Transform object.
Returns
The Transform converted to a geometry_msgs message type.

Definition at line 612 of file tf2_geometry_msgs.h.

◆ toMsg() [17/19]

geometry_msgs::Pose& tf2::toMsg ( const tf2::Transform in,
geometry_msgs::Pose &  out 
)
inline

Convert a tf2 Transform type to an equivalent geometry_msgs Pose message.

Pose

Parameters
inA tf2 Transform object.
outThe Transform converted to a geometry_msgs Pose message type.

Definition at line 433 of file tf2_geometry_msgs.h.

◆ toMsg() [18/19]

geometry_msgs::Vector3 tf2::toMsg ( const tf2::Vector3 &  in)
inline

Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Vector3

Parameters
inA tf2 Vector3 object.
Returns
The Vector3 converted to a geometry_msgs message type.

Definition at line 82 of file tf2_geometry_msgs.h.

◆ toMsg() [19/19]

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

Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h.

Point

Parameters
inA tf2 Vector3 object.
Returns
The Vector3 converted to a geometry_msgs message type.

Definition at line 191 of file tf2_geometry_msgs.h.

◆ transformCovariance()

geometry_msgs::PoseWithCovariance::_covariance_type tf2::transformCovariance ( const geometry_msgs::PoseWithCovariance::_covariance_type &  cov_in,
const tf2::Transform transform 
)
inline

Transform the covariance matrix of a PoseWithCovarianceStamped message to a new frame.

Parameters
t_inThe covariance matrix to transform.
transformThe timestamped transform to apply, as a TransformStamped message.
Returns
The transformed covariance matrix.

To transform a covariance matrix:

[R 0] COVARIANCE [R' 0 ] [0 R] [0 R']

Where: R is the rotation matrix (3x3). R' is the transpose of the rotation matrix. COVARIANCE is the 6x6 covariance matrix to be transformed.

Definition at line 822 of file tf2_geometry_msgs.h.



tf2_geometry_msgs
Author(s): Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:21