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

Namespaces

 impl
 

Classes

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

Typedefs

typedef std::pair< TimePoint, CompactFrameIDP_TimeAndFrameID
 
typedef uint64_t TransformableRequestHandle
 
typedef std::shared_ptr< TimeCacheInterfaceTimeCacheInterfacePtr
 
typedef std::chrono::nanoseconds Duration
 
typedef std::chrono::time_point< std::chrono::system_clock, DurationTimePoint
 
typedef std::chrono::duration< int, std::nanoIDuration
 
typedef uint32_t CompactFrameID
 

Enumerations

enum  TransformableResult
 
enum  TF2Error {
  TF2Error::NO_ERROR, TF2Error::LOOKUP_ERROR, TF2Error::CONNECTIVITY_ERROR, TF2Error::EXTRAPOLATION_ERROR,
  TF2Error::INVALID_ARGUMENT_ERROR, TF2Error::TIMEOUT_ERROR, TF2Error::TRANSFORM_ERROR
}
 

Functions

void doTransform (const T &data_in, T &data_out, const geometry_msgs::msg::TransformStamped &transform)
 
tf2::TimePoint getTimestamp (const T &t)
 
std::string getFrameId (const T &t)
 
std::array< std::array< double, 6 >, 6 > getCovarianceMatrix (const T &t)
 
tf2::TimePoint getTimestamp (const tf2::Stamped< P > &t)
 
std::string getFrameId (const tf2::Stamped< P > &t)
 
std::array< std::array< double, 6 >, 6 > getCovarianceMatrix (const tf2::WithCovarianceStamped< P > &t)
 
toMsg (const A &a)
 
void fromMsg (const A &, B &b)
 
void convert (const A &a, B &b)
 
void convert (const A &a1, A &a2)
 
std::array< std::array< double, 6 >, 6 > covarianceRowMajorToNested (const std::array< double, 36 > &row_major)
 
std::array< double, 36 > covarianceNestedToRowMajor (const std::array< std::array< double, 6 >, 6 > &nested_array)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Matrix3x3 &m, const Vector3 &v)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v, const Matrix3x3 &m)
 
TF2SIMD_FORCE_INLINE Matrix3x3 operator* (const Matrix3x3 &m1, const Matrix3x3 &m2)
 
TF2SIMD_FORCE_INLINE bool operator== (const Matrix3x3 &m1, const Matrix3x3 &m2)
 
 ATTRIBUTE_ALIGNED16 (class) QuadWord
 
TF2SIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q)
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q1, const Quaternion &q2)
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q, const Vector3 &w)
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const Vector3 &w, const Quaternion &q)
 
TF2SIMD_FORCE_INLINE tf2Scalar dot (const Quaternion &q1, const Quaternion &q2)
 
TF2SIMD_FORCE_INLINE tf2Scalar length (const Quaternion &q)
 
TF2SIMD_FORCE_INLINE tf2Scalar angle (const Quaternion &q1, const Quaternion &q2)
 
TF2SIMD_FORCE_INLINE tf2Scalar angleShortestPath (const Quaternion &q1, const Quaternion &q2)
 
TF2SIMD_FORCE_INLINE Quaternion inverse (const Quaternion &q)
 
TF2SIMD_FORCE_INLINE Quaternion slerp (const Quaternion &q1, const Quaternion &q2, const tf2Scalar &t)
 
TF2SIMD_FORCE_INLINE Vector3 quatRotate (const Quaternion &rotation, const Vector3 &v)
 
TF2SIMD_FORCE_INLINE Quaternion shortestArcQuat (const Vector3 &v0, const Vector3 &v1)
 
TF2SIMD_FORCE_INLINE Quaternion shortestArcQuatNormalize2 (Vector3 &v0, Vector3 &v1)
 
TF2SIMD_FORCE_INLINE bool operator== (const Transform &t1, const Transform &t2)
 
TF2SIMD_FORCE_INLINE Vector3 operator+ (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v, const tf2Scalar &s)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const tf2Scalar &s, const Vector3 &v)
 
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 tf2Scalar tf2Dot (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance2 (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance (const Vector3 &v1, const Vector3 &v2)
 
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 tf2Triple (const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
 
TF2SIMD_FORCE_INLINE Vector3 lerp (const Vector3 &v1, const Vector3 &v2, const tf2Scalar &t)
 
TF2SIMD_FORCE_INLINE void tf2SwapScalarEndian (const tf2Scalar &sourceVal, tf2Scalar &destVal)
 
TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec)
 
TF2SIMD_FORCE_INLINE void tf2UnSwapVector3Endian (Vector3 &vector)
 
TF2SIMD_FORCE_INLINE void tf2PlaneSpace1 (const Vector3 &n, Vector3 &p, Vector3 &q)
 
TimePoint get_now ()
 
Duration durationFromSec (double t_sec)
 
TimePoint timeFromSec (double t_sec)
 
double durationToSec (const tf2::Duration &input)
 
double timeToSec (const TimePoint &timepoint)
 
std::string displayTimePoint (const TimePoint &stamp)
 
bool operator== (const Stamped< T > &a, const Stamped< T > &b)
 
bool operator== (const WithCovarianceStamped< T > &a, const WithCovarianceStamped< T > &b)
 
void getEulerYPR (const A &a, double &yaw, double &pitch, double &roll)
 
double getYaw (const A &a)
 
getTransformIdentity ()
 
KDL::Frame gmTransformToKDL (const geometry_msgs::msg::TransformStamped &t)
 Convert a TransformStamped message to a KDL frame. More...
 
template<>
tf2::TimePoint getTimestamp (const geometry_msgs::msg::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<>
std::string getFrameId (const geometry_msgs::msg::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<>
void doTransform (const geometry_msgs::msg::Vector3Stamped &t_in, geometry_msgs::msg::Vector3Stamped &t_out, const geometry_msgs::msg::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...
 
geometry_msgs::msg::Vector3Stamped toMsg (const geometry_msgs::msg::Vector3Stamped &in)
 Trivial "conversion" function for Vector3 message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::msg::Vector3Stamped &msg, geometry_msgs::msg::Vector3Stamped &out)
 Trivial "conversion" function for Vector3 message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
template<>
tf2::TimePoint getTimestamp (const geometry_msgs::msg::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<>
std::string getFrameId (const geometry_msgs::msg::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<>
void doTransform (const geometry_msgs::msg::PointStamped &t_in, geometry_msgs::msg::PointStamped &t_out, const geometry_msgs::msg::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...
 
geometry_msgs::msg::PointStamped toMsg (const geometry_msgs::msg::PointStamped &in)
 Trivial "conversion" function for Point message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::msg::PointStamped &msg, geometry_msgs::msg::PointStamped &out)
 Trivial "conversion" function for Point message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
template<>
tf2::TimePoint getTimestamp (const geometry_msgs::msg::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<>
std::string getFrameId (const geometry_msgs::msg::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<>
void doTransform (const geometry_msgs::msg::PoseStamped &t_in, geometry_msgs::msg::PoseStamped &t_out, const geometry_msgs::msg::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...
 
geometry_msgs::msg::PoseStamped toMsg (const geometry_msgs::msg::PoseStamped &in)
 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::msg::PoseStamped &msg, geometry_msgs::msg::PoseStamped &out)
 Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
template<>
tf2::TimePoint getTimestamp (const geometry_msgs::msg::PoseWithCovarianceStamped &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<>
std::string getFrameId (const geometry_msgs::msg::PoseWithCovarianceStamped &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<>
std::array< std::array< double, 6 >, 6 > getCovarianceMatrix (const geometry_msgs::msg::PoseWithCovarianceStamped &t)
 Extract a covariance matrix from a PoseWithCovarianceStamped message. This function is a specialization of the getCovarianceMatrix template defined in tf2/convert.h. More...
 
template<>
void doTransform (const geometry_msgs::msg::PoseWithCovarianceStamped &t_in, geometry_msgs::msg::PoseWithCovarianceStamped &t_out, const geometry_msgs::msg::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...
 
geometry_msgs::msg::PoseWithCovarianceStamped toMsg (const geometry_msgs::msg::PoseWithCovarianceStamped &in)
 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::msg::PoseWithCovarianceStamped &msg, geometry_msgs::msg::PoseWithCovarianceStamped &out)
 Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
template<>
geometry_msgs::msg::PoseWithCovarianceStamped toMsg (const tf2::WithCovarianceStamped< tf2::Transform > &in)
 Convert a tf2 TransformWithCovarianceStamped type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
template<>
void fromMsg (const geometry_msgs::msg::PoseWithCovarianceStamped &in, tf2::WithCovarianceStamped< tf2::Transform > &out)
 Convert a PoseWithCovarianceStamped message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::msg::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...
 
void fromMsg (const geometry_msgs::msg::Quaternion &in, tf2::Quaternion &out)
 Convert a Quaternion message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
template<>
tf2::TimePoint getTimestamp (const geometry_msgs::msg::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<>
std::string getFrameId (const geometry_msgs::msg::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<>
void doTransform (const geometry_msgs::msg::QuaternionStamped &t_in, geometry_msgs::msg::QuaternionStamped &t_out, const geometry_msgs::msg::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...
 
geometry_msgs::msg::QuaternionStamped toMsg (const geometry_msgs::msg::QuaternionStamped &in)
 Trivial "conversion" function for Quaternion message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::msg::QuaternionStamped &msg, geometry_msgs::msg::QuaternionStamped &out)
 Trivial "conversion" function for Quaternion message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::msg::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...
 
void fromMsg (const geometry_msgs::msg::QuaternionStamped &in, tf2::Stamped< tf2::Quaternion > &out)
 Convert a QuaternionStamped message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::msg::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...
 
void fromMsg (const geometry_msgs::msg::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...
 
template<>
tf2::TimePoint getTimestamp (const geometry_msgs::msg::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<>
std::string getFrameId (const geometry_msgs::msg::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<>
void doTransform (const geometry_msgs::msg::TransformStamped &t_in, geometry_msgs::msg::TransformStamped &t_out, const geometry_msgs::msg::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...
 
geometry_msgs::msg::TransformStamped toMsg (const geometry_msgs::msg::TransformStamped &in)
 Trivial "conversion" function for Transform message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::msg::TransformStamped &msg, geometry_msgs::msg::TransformStamped &out)
 Convert a TransformStamped 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::msg::TransformStamped &in, tf2::Stamped< tf2::Transform > &out)
 Convert a TransformStamped message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::msg::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...
 
void toMsg (const tf2::Transform &in, geometry_msgs::msg::Pose &out)
 Convert a tf2 Transform type to an equivalent geometry_msgs Pose message. More...
 
void fromMsg (const geometry_msgs::msg::Pose &in, tf2::Transform &out)
 Convert a geometry_msgs Pose message to an equivalent tf2 Transform type. More...
 

Variables

 TransformAvailable
 
 TransformFailure
 
constexpr tf2::Duration TIMECACHE_DEFAULT_MAX_STORAGE_TIME
 

Detailed Description

Author
Wim Meeussen

Function Documentation

◆ gmTransformToKDL()

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

Convert a TransformStamped message to a KDL frame.

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

◆ getTimestamp() [1/6]

template<>
tf2::TimePoint tf2::getTimestamp ( const geometry_msgs::msg::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.

◆ getFrameId() [1/6]

template<>
std::string tf2::getFrameId ( const geometry_msgs::msg::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.

◆ doTransform() [1/6]

template<>
void tf2::doTransform ( const geometry_msgs::msg::Vector3Stamped &  t_in,
geometry_msgs::msg::Vector3Stamped &  t_out,
const geometry_msgs::msg::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 timestamped Vector3 message.
t_outThe transformed vector, as a timestamped Vector3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ toMsg() [1/12]

geometry_msgs::msg::Vector3Stamped tf2::toMsg ( const geometry_msgs::msg::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.

◆ fromMsg() [1/12]

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

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

Parameters
msgA Vector3Stamped message.
outThe input argument.

◆ getTimestamp() [2/6]

template<>
tf2::TimePoint tf2::getTimestamp ( const geometry_msgs::msg::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.

◆ getFrameId() [2/6]

template<>
std::string tf2::getFrameId ( const geometry_msgs::msg::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.

◆ doTransform() [2/6]

template<>
void tf2::doTransform ( const geometry_msgs::msg::PointStamped &  t_in,
geometry_msgs::msg::PointStamped &  t_out,
const geometry_msgs::msg::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 timestamped Point3 message.
t_outThe transformed point, as a timestamped Point3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ toMsg() [2/12]

geometry_msgs::msg::PointStamped tf2::toMsg ( const geometry_msgs::msg::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.

◆ fromMsg() [2/12]

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

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

Parameters
msgA PointStamped message.
outThe input argument.

◆ getTimestamp() [3/6]

template<>
tf2::TimePoint tf2::getTimestamp ( const geometry_msgs::msg::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.

◆ getFrameId() [3/6]

template<>
std::string tf2::getFrameId ( const geometry_msgs::msg::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.

◆ doTransform() [3/6]

template<>
void tf2::doTransform ( const geometry_msgs::msg::PoseStamped &  t_in,
geometry_msgs::msg::PoseStamped &  t_out,
const geometry_msgs::msg::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 timestamped Pose3 message.
t_outThe transformed pose, as a timestamped Pose3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ toMsg() [3/12]

geometry_msgs::msg::PoseStamped tf2::toMsg ( const geometry_msgs::msg::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.

◆ fromMsg() [3/12]

void tf2::fromMsg ( const geometry_msgs::msg::PoseStamped &  msg,
geometry_msgs::msg::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.

◆ getTimestamp() [4/6]

template<>
tf2::TimePoint tf2::getTimestamp ( const geometry_msgs::msg::PoseWithCovarianceStamped &  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.

PoseWithCovarianceStamped

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

◆ getFrameId() [4/6]

template<>
std::string tf2::getFrameId ( const geometry_msgs::msg::PoseWithCovarianceStamped &  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
tPoseWithCovarianceStamped message to extract the frame ID from.
Returns
A string containing the frame ID of the message.

◆ getCovarianceMatrix()

template<>
std::array<std::array<double, 6>, 6> tf2::getCovarianceMatrix ( const geometry_msgs::msg::PoseWithCovarianceStamped &  t)
inline

Extract a covariance matrix from a PoseWithCovarianceStamped message. This function is a specialization of the getCovarianceMatrix template defined in tf2/convert.h.

Parameters
tPoseWithCovarianceStamped message to extract the covariance matrix from.
Returns
A nested-array representation of the covariance matrix from the message.

◆ doTransform() [4/6]

template<>
void tf2::doTransform ( const geometry_msgs::msg::PoseWithCovarianceStamped &  t_in,
geometry_msgs::msg::PoseWithCovarianceStamped &  t_out,
const geometry_msgs::msg::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 timestamped Pose3 message with covariance.
t_outThe transformed pose, as a timestamped Pose3 message with covariance.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ toMsg() [4/12]

geometry_msgs::msg::PoseWithCovarianceStamped tf2::toMsg ( const geometry_msgs::msg::PoseWithCovarianceStamped &  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 PoseWithCovarianceStamped message.
Returns
The input argument.

◆ fromMsg() [4/12]

void tf2::fromMsg ( const geometry_msgs::msg::PoseWithCovarianceStamped &  msg,
geometry_msgs::msg::PoseWithCovarianceStamped &  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 PoseWithCovarianceStamped message.
outThe input argument.

◆ toMsg() [5/12]

template<>
geometry_msgs::msg::PoseWithCovarianceStamped tf2::toMsg ( const tf2::WithCovarianceStamped< tf2::Transform > &  in)
inline

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

Parameters
inA instance of the tf2::Transform specialization of the tf2::WithCovarianceStamped template.
Returns
The TransformWithCovarianceStamped converted to a geometry_msgs PoseStamped message type.

◆ fromMsg() [5/12]

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

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

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

◆ toMsg() [6/12]

geometry_msgs::msg::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.

◆ fromMsg() [6/12]

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

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

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

◆ getTimestamp() [5/6]

template<>
tf2::TimePoint tf2::getTimestamp ( const geometry_msgs::msg::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.

◆ getFrameId() [5/6]

template<>
std::string tf2::getFrameId ( const geometry_msgs::msg::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.

◆ doTransform() [5/6]

template<>
void tf2::doTransform ( const geometry_msgs::msg::QuaternionStamped &  t_in,
geometry_msgs::msg::QuaternionStamped &  t_out,
const geometry_msgs::msg::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 timestamped Quaternion3 message.
t_outThe transformed quaternion, as a timestamped Quaternion3 message.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ toMsg() [7/12]

geometry_msgs::msg::QuaternionStamped tf2::toMsg ( const geometry_msgs::msg::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.

◆ fromMsg() [7/12]

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

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

Parameters
msgA QuaternionStamped message.
outThe input argument.

◆ toMsg() [8/12]

geometry_msgs::msg::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
inA instance of the tf2::Quaternion specialization of the tf2::Stamped template.
Returns
The QuaternionStamped converted to a geometry_msgs QuaternionStamped message type.

◆ fromMsg() [8/12]

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

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

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

◆ toMsg() [9/12]

geometry_msgs::msg::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.

◆ fromMsg() [9/12]

void tf2::fromMsg ( const geometry_msgs::msg::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.

◆ getTimestamp() [6/6]

template<>
tf2::TimePoint tf2::getTimestamp ( const geometry_msgs::msg::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.

◆ getFrameId() [6/6]

template<>
std::string tf2::getFrameId ( const geometry_msgs::msg::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.

◆ doTransform() [6/6]

template<>
void tf2::doTransform ( const geometry_msgs::msg::TransformStamped &  t_in,
geometry_msgs::msg::TransformStamped &  t_out,
const geometry_msgs::msg::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.

◆ toMsg() [10/12]

geometry_msgs::msg::TransformStamped tf2::toMsg ( const geometry_msgs::msg::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.

◆ fromMsg() [10/12]

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

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

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

◆ fromMsg() [11/12]

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

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

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

◆ toMsg() [11/12]

geometry_msgs::msg::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 TransformStamped converted to a geometry_msgs TransformStamped message type.

◆ toMsg() [12/12]

void tf2::toMsg ( const tf2::Transform in,
geometry_msgs::msg::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. This section is about converting

◆ fromMsg() [12/12]

void tf2::fromMsg ( const geometry_msgs::msg::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.