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)
 
void doTransform (const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
 
template<>
void doTransform (const tf2::Stamped< KDL::Vector > &t_in, tf2::Stamped< KDL::Vector > &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an KDL-specific Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const tf2::Stamped< KDL::Twist > &t_in, tf2::Stamped< KDL::Twist > &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an KDL-specific Twist type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const tf2::Stamped< KDL::Wrench > &t_in, tf2::Stamped< KDL::Wrench > &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an KDL-specific Wrench type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const tf2::Stamped< KDL::Frame > &t_in, tf2::Stamped< KDL::Frame > &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to a KDL-specific Frame data type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
void fromMsg (const A &, B &b)
 
void fromMsg (const geometry_msgs::PointStamped &msg, tf2::Stamped< KDL::Vector > &out)
 Convert a PointStamped message type to a stamped KDL-specific Vector type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::TwistStamped &msg, tf2::Stamped< KDL::Twist > &out)
 Convert a TwistStamped message type to a stamped KDL-specific Twist type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::WrenchStamped &msg, tf2::Stamped< KDL::Wrench > &out)
 Convert a WrenchStamped message type to a stamped KDL-specific Wrench type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::Pose &msg, KDL::Frame &out)
 Convert a Pose message type to a KDL Frame. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< KDL::Frame > &out)
 Convert a Pose message transform type to a stamped KDL Frame. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void getEulerYPR (const A &a, double &yaw, double &pitch, double &roll)
 
const std::string & getFrameId (const T &t)
 
const std::string & getFrameId (const tf2::Stamped< P > &t)
 
const ros::TimegetTimestamp (const T &t)
 
const ros::TimegetTimestamp (const tf2::Stamped< P > &t)
 
getTransformIdentity ()
 
double getYaw (const A &a)
 
TF2SIMD_FORCE_INLINE Quaternion inverse (const Quaternion &q)
 
geometry_msgs::TransformStamped kdlToTransform (const KDL::Frame &k)
 Convert an KDL Frame to the equivalent geometry_msgs message type. More...
 
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 Vector3 &v1, const Vector3 &v2)
 
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 Vector3 operator* (const Vector3 &v, const tf2Scalar &s)
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const Vector3 &w, const Quaternion &q)
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const tf2Scalar &s, const Vector3 &v)
 
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 Vector3 operator+ (const Vector3 &v1, const Vector3 &v2)
 
TF2SIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v)
 
TF2SIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q)
 
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)
 
bool operator== (const Stamped< T > &a, const Stamped< T > &b)
 
TF2SIMD_FORCE_INLINE bool operator== (const Matrix3x3 &m1, const Matrix3x3 &m2)
 
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 tf2::Stamped< KDL::Vector > &in)
 Convert a stamped KDL Vector type to a PointStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::TwistStamped toMsg (const tf2::Stamped< KDL::Twist > &in)
 Convert a stamped KDL Twist type to a TwistStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::WrenchStamped toMsg (const tf2::Stamped< KDL::Wrench > &in)
 Convert a stamped KDL Wrench type to a WrenchStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Pose toMsg (const KDL::Frame &in)
 Convert a stamped KDL Frame type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseStamped toMsg (const tf2::Stamped< KDL::Frame > &in)
 Convert a stamped KDL Frame type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void transformMsgToTF2 (const geometry_msgs::Transform &msg, tf2::Transform &tf2)
 
void transformTF2ToMsg (const tf2::Transform &tf2, geometry_msgs::Transform &msg)
 
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::TransformStamped &msg, ros::Time stamp, const std::string &frame_id, const std::string &child_frame_id)
 
KDL::Frame transformToKDL (const geometry_msgs::TransformStamped &t)
 Convert a timestamped transform to the equivalent KDL data type. More...
 

Variables

 FullPath
 
 Identity
 
static double QUATERNION_NORMALIZATION_TOLERANCE
 
 SourceParentOfTarget
 
 TargetParentOfSource
 
 TransformAvailable
 
 TransformFailure
 

Detailed Description

Author
Wim Meeussen

Function Documentation

◆ doTransform() [1/4]

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

Apply a geometry_msgs TransformStamped to an KDL-specific 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 KDL Vector data type.
t_outThe transformed vector, as a timestamped KDL Vector data type.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 84 of file tf2_kdl.h.

◆ doTransform() [2/4]

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

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

Parameters
t_inThe twist to transform, as a timestamped KDL Twist data type.
t_outThe transformed Twist, as a timestamped KDL Frame data type.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 132 of file tf2_kdl.h.

◆ doTransform() [3/4]

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

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

Parameters
t_inThe wrench to transform, as a timestamped KDL Wrench data type.
t_outThe transformed Wrench, as a timestamped KDL Frame data type.
transformThe timestamped transform to apply, as a TransformStamped message.

Definition at line 187 of file tf2_kdl.h.

◆ doTransform() [4/4]

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

Apply a geometry_msgs TransformStamped to a KDL-specific Frame data type. This function is a specialization of the doTransform template defined in tf2/convert.h.

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

Definition at line 244 of file tf2_kdl.h.

◆ fromMsg() [1/5]

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

Convert a PointStamped message type to a stamped KDL-specific Vector type. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe PointStamped message to convert.
outThe point converted to a timestamped KDL Vector.

Definition at line 112 of file tf2_kdl.h.

◆ fromMsg() [2/5]

void tf2::fromMsg ( const geometry_msgs::TwistStamped &  msg,
tf2::Stamped< KDL::Twist > &  out 
)
inline

Convert a TwistStamped message type to a stamped KDL-specific Twist type. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe TwistStamped message to convert.
outThe twist converted to a timestamped KDL Twist.

Definition at line 163 of file tf2_kdl.h.

◆ fromMsg() [3/5]

void tf2::fromMsg ( const geometry_msgs::WrenchStamped &  msg,
tf2::Stamped< KDL::Wrench > &  out 
)
inline

Convert a WrenchStamped message type to a stamped KDL-specific Wrench type. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe WrenchStamped message to convert.
outThe wrench converted to a timestamped KDL Wrench.

Definition at line 218 of file tf2_kdl.h.

◆ fromMsg() [4/5]

void tf2::fromMsg ( const geometry_msgs::Pose &  msg,
KDL::Frame out 
)
inline

Convert a Pose message type to a KDL Frame. 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 KDL Frame.

Definition at line 271 of file tf2_kdl.h.

◆ fromMsg() [5/5]

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

Convert a Pose message transform type to a stamped KDL Frame. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe PoseStamped message to convert.
outThe pose converted to a timestamped KDL Frame.

Definition at line 300 of file tf2_kdl.h.

◆ kdlToTransform()

geometry_msgs::TransformStamped tf2::kdlToTransform ( const KDL::Frame k)
inline

Convert an KDL Frame to the equivalent geometry_msgs message type.

Parameters
kThe transform to convert, as an KDL Frame.
Returns
The transform converted to a TransformStamped message.

Definition at line 63 of file tf2_kdl.h.

◆ toMsg() [1/5]

geometry_msgs::PointStamped tf2::toMsg ( const tf2::Stamped< KDL::Vector > &  in)
inline

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

Parameters
inThe timestamped KDL Vector to convert.
Returns
The vector converted to a PointStamped message.

Definition at line 95 of file tf2_kdl.h.

◆ toMsg() [2/5]

geometry_msgs::TwistStamped tf2::toMsg ( const tf2::Stamped< KDL::Twist > &  in)
inline

Convert a stamped KDL Twist type to a TwistStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe timestamped KDL Twist to convert.
Returns
The twist converted to a TwistStamped message.

Definition at line 143 of file tf2_kdl.h.

◆ toMsg() [3/5]

geometry_msgs::WrenchStamped tf2::toMsg ( const tf2::Stamped< KDL::Wrench > &  in)
inline

Convert a stamped KDL Wrench type to a WrenchStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe timestamped KDL Wrench to convert.
Returns
The wrench converted to a WrenchStamped message.

Definition at line 198 of file tf2_kdl.h.

◆ toMsg() [4/5]

geometry_msgs::Pose tf2::toMsg ( const KDL::Frame in)
inline

Convert a stamped KDL Frame type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe timestamped KDL Frame to convert.
Returns
The frame converted to a Pose message.

Definition at line 255 of file tf2_kdl.h.

◆ toMsg() [5/5]

geometry_msgs::PoseStamped tf2::toMsg ( const tf2::Stamped< KDL::Frame > &  in)
inline

Convert a stamped KDL Frame type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe timestamped KDL Frame to convert.
Returns
The frame converted to a PoseStamped message.

Definition at line 285 of file tf2_kdl.h.

◆ transformToKDL()

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

Convert a timestamped transform to the equivalent KDL data type.

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

Definition at line 51 of file tf2_kdl.h.



tf2_kdl
Author(s): Wim Meeussen
autogenerated on Mon Jun 27 2022 02:43:23