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

Namespaces

 filter_failure_reasons
 

Classes

class  Matrix3x3
 The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Quaternion, Transform and Vector3. Make sure to only include a pure orthogonal matrix without scaling. More...
 
struct  Matrix3x3DoubleData
 for serialization More...
 
struct  Matrix3x3FloatData
 for serialization More...
 
class  MessageFilter
 Follows the patterns set by the message_filters package to implement a filter which only passes messages through once there is transform data available. More...
 
class  MessageFilterBase
 
class  Quaternion
 The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x3, Vector3 and Transform. More...
 
class  Stamped
 The data type which will be cross compatable with geometry_msgs This is the tf datatype equivilant of a MessageStamped. More...
 
class  StampedTransform
 The Stamped Transform datatype used by tf. More...
 
class  tfVector4
 
class  TimeCache
 A class to keep a sorted linked list in time This builds and maintains a list of timestamped data. And provides lookup functions to get data out as a function of time. More...
 
class  Transform
 The Transform class supports rigid transforms with only translation and rotation and no scaling/shear. It can be used in combination with Vector3, Quaternion and Matrix3x3 linear algebra classes. More...
 
class  TransformBroadcaster
 This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message. More...
 
struct  TransformDoubleData
 
class  Transformer
 A Class which provides coordinate transforms between any two frames in a system. More...
 
struct  TransformFloatData
 for serialization More...
 
class  TransformListener
 This class inherits from Transformer and automatically subscribes to ROS transform messages. More...
 
struct  TransformLists
 An internal representation of transform chains. More...
 
class  TransformStorage
 Storage for transforms and their parent. More...
 
class  Vector3
 Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte alignment when Vector3 is stored in containers. This extra component can be used by derived classes (Quaternion?) or by user Ideally, this class should be replaced by a platform optimized SIMD version that keeps the data in registers. More...
 
struct  Vector3DoubleData
 
struct  Vector3FloatData
 

Typedefs

typedef uint32_t CompactFrameID
 
typedef tf2::ConnectivityException ConnectivityException
 
typedef tf2::ExtrapolationException ExtrapolationException
 
typedef filter_failure_reasons::FilterFailureReason FilterFailureReason
 
typedef tf2::InvalidArgumentException InvalidArgument
 
typedef tf2::LookupException LookupException
 
typedef std::pair< ros::Time, CompactFrameIDP_TimeAndFrameID
 
typedef tf::Vector3 Point
 
typedef tf::Transform Pose
 
typedef tf2::TransformException TransformException
 

Enumerations

enum  ErrorValues { NO_ERROR = 0, LOOKUP_ERROR, CONNECTIVITY_ERROR, EXTRAPOLATION_ERROR }
 
enum  ExtrapolationMode { ONE_VALUE, INTERPOLATE, EXTRAPOLATE_BACK, EXTRAPOLATE_FORWARD }
 

Functions

 __attribute__ ((deprecated)) static inline std
 
class tf::Vector3 __attribute__ ((aligned(16)))
 
TFSIMD_FORCE_INLINE tfScalar angle (const Quaternion &q1, const Quaternion &q2)
 Return the ***half*** angle between two quaternions. More...
 
TFSIMD_FORCE_INLINE tfScalar angleShortestPath (const Quaternion &q1, const Quaternion &q2)
 Return the shortest angle between two quaternions. More...
 
void assertQuaternionValid (const tf::Quaternion &q)
 Throw InvalidArgument if quaternion is malformed. More...
 
void assertQuaternionValid (const geometry_msgs::Quaternion &q)
 Throw InvalidArgument if quaternion is malformed. More...
 
 ATTRIBUTE_ALIGNED16 (class) QuadWord
 The QuadWord class is base class for Vector3 and Quaternion. Some issues under PS3 Linux with IBM 2.1 SDK, gcc compiler prevent from using aligned quadword. More...
 
static tf::Quaternion createIdentityQuaternion ()
 construct an Identity Quaternion More...
 
static tf::Quaternion createQuaternionFromRPY (double roll, double pitch, double yaw)
 construct a Quaternion from Fixed angles More...
 
static Quaternion createQuaternionFromYaw (double yaw)
 construct a Quaternion from yaw only More...
 
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw (double roll, double pitch, double yaw)
 construct a Quaternion Message from Fixed angles More...
 
static geometry_msgs::Quaternion createQuaternionMsgFromYaw (double yaw)
 construct a Quaternion Message from yaw only More...
 
TFSIMD_FORCE_INLINE tfScalar dot (const Quaternion &q1, const Quaternion &q2)
 Calculate the dot product between two quaternions. More...
 
std::string getPrefixParam (ros::NodeHandle &nh)
 Get the tf_prefix from the parameter server. More...
 
static double getYaw (const Quaternion &bt_q)
 Helper function for getting yaw from a Quaternion. More...
 
static double getYaw (const geometry_msgs::Quaternion &msg_q)
 Helper function for getting yaw from a Quaternion message. More...
 
TFSIMD_FORCE_INLINE Quaternion inverse (const Quaternion &q)
 Return the inverse of a quaternion. More...
 
TFSIMD_FORCE_INLINE tfScalar length (const Quaternion &q)
 Return the length of a quaternion. More...
 
TFSIMD_FORCE_INLINE Vector3 lerp (const Vector3 &v1, const Vector3 &v2, const tfScalar &t)
 Return the linear interpolation between two vectors. More...
 
TFSIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v1, const Vector3 &v2)
 Return the elementwise product of two vectors. More...
 
TFSIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q1, const Quaternion &q2)
 Return the product of two quaternions. More...
 
TFSIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q, const Vector3 &w)
 
TFSIMD_FORCE_INLINE Quaternion operator* (const Vector3 &w, const Quaternion &q)
 
TFSIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v, const tfScalar &s)
 Return the vector scaled by s. More...
 
TFSIMD_FORCE_INLINE Vector3 operator* (const tfScalar &s, const Vector3 &v)
 Return the vector scaled by s. More...
 
TFSIMD_FORCE_INLINE Vector3 operator* (const Matrix3x3 &m, const Vector3 &v)
 
TFSIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v, const Matrix3x3 &m)
 
TFSIMD_FORCE_INLINE Matrix3x3 operator* (const Matrix3x3 &m1, const Matrix3x3 &m2)
 
TFSIMD_FORCE_INLINE Vector3 operator+ (const Vector3 &v1, const Vector3 &v2)
 Return the sum of two vectors (Point symantics) More...
 
TFSIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q)
 Return the negative of a quaternion. More...
 
TFSIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v1, const Vector3 &v2)
 Return the difference between two vectors. More...
 
TFSIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v)
 Return the negative of the vector. More...
 
TFSIMD_FORCE_INLINE Vector3 operator/ (const Vector3 &v, const tfScalar &s)
 Return the vector inversely scaled by s. More...
 
TFSIMD_FORCE_INLINE Vector3 operator/ (const Vector3 &v1, const Vector3 &v2)
 Return the vector inversely scaled by s. More...
 
template<typename T >
bool operator== (const Stamped< T > &a, const Stamped< T > &b)
 Comparison Operator for Stamped datatypes. More...
 
static bool operator== (const StampedTransform &a, const StampedTransform &b)
 Comparison operator for StampedTransform. More...
 
TFSIMD_FORCE_INLINE bool operator== (const Transform &t1, const Transform &t2)
 Test if two transforms have all elements equal. More...
 
TFSIMD_FORCE_INLINE bool operator== (const Matrix3x3 &m1, const Matrix3x3 &m2)
 Equality operator between two matrices It will test all elements are equal. More...
 
static void pointMsgToTF (const geometry_msgs::Point &msg_v, Point &bt_v)
 convert Point msg to Point More...
 
static void pointStampedMsgToTF (const geometry_msgs::PointStamped &msg, Stamped< Point > &bt)
 convert PointStamped msg to Stamped<Point> More...
 
static void pointStampedTFToMsg (const Stamped< Point > &bt, geometry_msgs::PointStamped &msg)
 convert Stamped<Point> to PointStamped msg More...
 
static void pointTFToMsg (const Point &bt_v, geometry_msgs::Point &msg_v)
 convert Point to Point msg More...
 
static void poseMsgToTF (const geometry_msgs::Pose &msg, Pose &bt)
 convert Pose msg to Pose More...
 
static void poseStampedMsgToTF (const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
 convert PoseStamped msg to Stamped<Pose> More...
 
static void poseStampedTFToMsg (const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
 convert Stamped<Pose> to PoseStamped msg More...
 
static void poseTFToMsg (const Pose &bt, geometry_msgs::Pose &msg)
 convert Pose to Pose msg More...
 
static void quaternionMsgToTF (const geometry_msgs::Quaternion &msg, Quaternion &bt)
 convert Quaternion msg to Quaternion More...
 
static void quaternionStampedMsgToTF (const geometry_msgs::QuaternionStamped &msg, Stamped< Quaternion > &bt)
 convert QuaternionStamped msg to Stamped<Quaternion> More...
 
static void quaternionStampedTFToMsg (const Stamped< Quaternion > &bt, geometry_msgs::QuaternionStamped &msg)
 convert Stamped<Quaternion> to QuaternionStamped msg More...
 
static void quaternionTFToMsg (const Quaternion &bt, geometry_msgs::Quaternion &msg)
 convert Quaternion to Quaternion msg More...
 
TFSIMD_FORCE_INLINE Vector3 quatRotate (const Quaternion &rotation, const Vector3 &v)
 
std::string remap (const std::string &frame_id) __attribute__((deprecated))
 resolve names More...
 
std::string resolve (const std::string &prefix, const std::string &frame_name)
 resolve tf names More...
 
TFSIMD_FORCE_INLINE Quaternion shortestArcQuat (const Vector3 &v0, const Vector3 &v1)
 
TFSIMD_FORCE_INLINE Quaternion shortestArcQuatNormalize2 (Vector3 &v0, Vector3 &v1)
 
TFSIMD_FORCE_INLINE Quaternion slerp (const Quaternion &q1, const Quaternion &q2, const tfScalar &t)
 Return the result of spherical linear interpolation betwen two quaternions. More...
 
std::string strip_leading_slash (const std::string &frame_name)
 
TFSIMD_FORCE_INLINE tfScalar tfAngle (const Vector3 &v1, const Vector3 &v2)
 Return the angle between two vectors. More...
 
TFSIMD_FORCE_INLINE Vector3 tfCross (const Vector3 &v1, const Vector3 &v2)
 Return the cross product of two vectors. More...
 
TFSIMD_FORCE_INLINE tfScalar tfDistance (const Vector3 &v1, const Vector3 &v2)
 Return the distance between two vectors. More...
 
TFSIMD_FORCE_INLINE tfScalar tfDistance2 (const Vector3 &v1, const Vector3 &v2)
 Return the distance squared between two vectors. More...
 
TFSIMD_FORCE_INLINE tfScalar tfDot (const Vector3 &v1, const Vector3 &v2)
 Return the dot product between two vectors. More...
 
TFSIMD_FORCE_INLINE void tfPlaneSpace1 (const Vector3 &n, Vector3 &p, Vector3 &q)
 
TFSIMD_FORCE_INLINE void tfSwapScalarEndian (const tfScalar &sourceVal, tfScalar &destVal)
 tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More...
 
TFSIMD_FORCE_INLINE void tfSwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec)
 tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More...
 
TFSIMD_FORCE_INLINE tfScalar tfTriple (const Vector3 &v1, const Vector3 &v2, const Vector3 &v3)
 
TFSIMD_FORCE_INLINE void tfUnSwapVector3Endian (Vector3 &vector)
 tfUnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More...
 
static void transformMsgToTF (const geometry_msgs::Transform &msg, Transform &bt)
 convert Transform msg to Transform More...
 
static void transformStampedMsgToTF (const geometry_msgs::TransformStamped &msg, StampedTransform &bt)
 convert TransformStamped msg to tf::StampedTransform More...
 
static void transformStampedTFToMsg (const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
 convert tf::StampedTransform to TransformStamped msg More...
 
static void transformTFToMsg (const Transform &bt, geometry_msgs::Transform &msg)
 convert Transform to Transform msg More...
 
static void vector3MsgToTF (const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v)
 convert Vector3 msg to Vector3 More...
 
static void vector3StampedMsgToTF (const geometry_msgs::Vector3Stamped &msg, Stamped< Vector3 > &bt)
 convert Vector3Stamped msg to Stamped<Vector3> More...
 
static void vector3StampedTFToMsg (const Stamped< Vector3 > &bt, geometry_msgs::Vector3Stamped &msg)
 convert Stamped<Vector3> to Vector3Stamped msg More...
 
static void vector3TFToMsg (const Vector3 &bt_v, geometry_msgs::Vector3 &msg_v)
 convert Vector3 to Vector3 msg More...
 

Variables

tf::tfVector4 __attribute__
 
static const double QUATERNION_TOLERANCE = 0.1f
 

Detailed Description

Author
Tully Foote

Typedef Documentation

typedef uint32_t tf::CompactFrameID

Definition at line 50 of file time_cache.h.

Definition at line 43 of file exceptions.h.

Definition at line 44 of file exceptions.h.

Definition at line 75 of file message_filter.h.

Definition at line 45 of file exceptions.h.

Definition at line 42 of file exceptions.h.

Definition at line 51 of file time_cache.h.

Definition at line 49 of file transform_datatypes.h.

Definition at line 50 of file transform_datatypes.h.

Definition at line 41 of file exceptions.h.

Enumeration Type Documentation

Enumerator
NO_ERROR 
LOOKUP_ERROR 
CONNECTIVITY_ERROR 
EXTRAPOLATION_ERROR 

Definition at line 61 of file tf.h.

Enumerator
ONE_VALUE 
INTERPOLATE 
EXTRAPOLATE_BACK 
EXTRAPOLATE_FORWARD 

Definition at line 47 of file time_cache.h.

Function Documentation

tf::__attribute__ ( (deprecated)  )
Deprecated:
This has been renamed to tf::resolve

Definition at line 59 of file tf.h.

class tf::Vector3 tf::__attribute__ ( (aligned(16))  )
TFSIMD_FORCE_INLINE tfScalar tf::angle ( const Quaternion q1,
const Quaternion q2 
)

Return the ***half*** angle between two quaternions.

Definition at line 405 of file Quaternion.h.

TFSIMD_FORCE_INLINE tfScalar tf::angleShortestPath ( const Quaternion q1,
const Quaternion q2 
)

Return the shortest angle between two quaternions.

Definition at line 412 of file Quaternion.h.

void tf::assertQuaternionValid ( const tf::Quaternion q)
inline

Throw InvalidArgument if quaternion is malformed.

Definition at line 393 of file tf.h.

void tf::assertQuaternionValid ( const geometry_msgs::Quaternion &  q)
inline

Throw InvalidArgument if quaternion is malformed.

Definition at line 411 of file tf.h.

tf::ATTRIBUTE_ALIGNED16 ( class  )

The QuadWord class is base class for Vector3 and Quaternion. Some issues under PS3 Linux with IBM 2.1 SDK, gcc compiler prevent from using aligned quadword.

Return the x value

Return the y value

Return the z value

Set the x value

Set the y value

Set the z value

Set the w value

Return the x value

Return the y value

Return the z value

Return the w value

operator tfScalar*() replaces operator[], using implicit conversion. We added operator != and operator == to avoid pointer comparisons.

Set x,y,z and zero w

Parameters
xValue of x
yValue of y
zValue of z

Set the values

Parameters
xValue of x
yValue of y
zValue of z
wValue of w

No initialization constructor

Three argument constructor (zeros w)

Parameters
xValue of x
yValue of y
zValue of z

Initializing constructor

Parameters
xValue of x
yValue of y
zValue of z
wValue of w

Set each element to the max of the current values and the values of another QuadWord

Parameters
otherThe other QuadWord to compare with

Set each element to the min of the current values and the values of another QuadWord

Parameters
otherThe other QuadWord to compare with

Definition at line 34 of file QuadWord.h.

static tf::Quaternion tf::createIdentityQuaternion ( )
inlinestatic

construct an Identity Quaternion

Returns
The quaternion constructed

Definition at line 193 of file transform_datatypes.h.

static tf::Quaternion tf::createQuaternionFromRPY ( double  roll,
double  pitch,
double  yaw 
)
inlinestatic

construct a Quaternion from Fixed angles

Parameters
rollThe roll about the X axis
pitchThe pitch about the Y axis
yawThe yaw about the Z axis
Returns
The quaternion constructed

Definition at line 150 of file transform_datatypes.h.

static Quaternion tf::createQuaternionFromYaw ( double  yaw)
inlinestatic

construct a Quaternion from yaw only

Parameters
yawThe yaw about the Z axis
Returns
The quaternion constructed

Definition at line 160 of file transform_datatypes.h.

static geometry_msgs::Quaternion tf::createQuaternionMsgFromRollPitchYaw ( double  roll,
double  pitch,
double  yaw 
)
inlinestatic

construct a Quaternion Message from Fixed angles

Parameters
rollThe roll about the X axis
pitchThe pitch about the Y axis
yawThe yaw about the Z axis
Returns
The quaternion constructed

Definition at line 184 of file transform_datatypes.h.

static geometry_msgs::Quaternion tf::createQuaternionMsgFromYaw ( double  yaw)
inlinestatic

construct a Quaternion Message from yaw only

Parameters
yawThe yaw about the Z axis
Returns
The quaternion constructed

Definition at line 170 of file transform_datatypes.h.

TFSIMD_FORCE_INLINE tfScalar tf::dot ( const Quaternion q1,
const Quaternion q2 
)

Calculate the dot product between two quaternions.

Definition at line 390 of file Quaternion.h.

std::string tf::getPrefixParam ( ros::NodeHandle nh)
inline

Get the tf_prefix from the parameter server.

Parameters
nhThe node handle to use to lookup the parameter.
Returns
The tf_prefix value for this NodeHandle

Definition at line 54 of file transform_listener.h.

static double tf::getYaw ( const Quaternion bt_q)
inlinestatic

Helper function for getting yaw from a Quaternion.

Definition at line 131 of file transform_datatypes.h.

static double tf::getYaw ( const geometry_msgs::Quaternion &  msg_q)
inlinestatic

Helper function for getting yaw from a Quaternion message.

Definition at line 138 of file transform_datatypes.h.

TFSIMD_FORCE_INLINE Quaternion tf::inverse ( const Quaternion q)

Return the inverse of a quaternion.

Definition at line 419 of file Quaternion.h.

TFSIMD_FORCE_INLINE tfScalar tf::length ( const Quaternion q)

Return the length of a quaternion.

Definition at line 398 of file Quaternion.h.

TFSIMD_FORCE_INLINE Vector3 tf::lerp ( const Vector3 v1,
const Vector3 v2,
const tfScalar t 
)

Return the linear interpolation between two vectors.

Parameters
v1One vector
v2The other vector
tThe ration of this to v (t = 0 => return v1, t=1 => return v2)

Definition at line 456 of file Vector3.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator* ( const Vector3 v1,
const Vector3 v2 
)

Return the elementwise product of two vectors.

Definition at line 361 of file Vector3.h.

TFSIMD_FORCE_INLINE Quaternion tf::operator* ( const Quaternion q1,
const Quaternion q2 
)

Return the product of two quaternions.

Definition at line 363 of file Quaternion.h.

TFSIMD_FORCE_INLINE Quaternion tf::operator* ( const Quaternion q,
const Vector3 w 
)

Definition at line 371 of file Quaternion.h.

TFSIMD_FORCE_INLINE Quaternion tf::operator* ( const Vector3 w,
const Quaternion q 
)

Definition at line 380 of file Quaternion.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator* ( const Vector3 v,
const tfScalar s 
)

Return the vector scaled by s.

Definition at line 381 of file Vector3.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator* ( const tfScalar s,
const Vector3 v 
)

Return the vector scaled by s.

Definition at line 388 of file Vector3.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator* ( const Matrix3x3 m,
const Vector3 v 
)

Definition at line 602 of file Matrix3x3.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator* ( const Vector3 v,
const Matrix3x3 m 
)

Definition at line 609 of file Matrix3x3.h.

TFSIMD_FORCE_INLINE Matrix3x3 tf::operator* ( const Matrix3x3 m1,
const Matrix3x3 m2 
)

Definition at line 615 of file Matrix3x3.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator+ ( const Vector3 v1,
const Vector3 v2 
)

Return the sum of two vectors (Point symantics)

Definition at line 354 of file Vector3.h.

TFSIMD_FORCE_INLINE Quaternion tf::operator- ( const Quaternion q)

Return the negative of a quaternion.

Definition at line 354 of file Quaternion.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator- ( const Vector3 v1,
const Vector3 v2 
)

Return the difference between two vectors.

Definition at line 368 of file Vector3.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator- ( const Vector3 v)

Return the negative of the vector.

Definition at line 374 of file Vector3.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator/ ( const Vector3 v,
const tfScalar s 
)

Return the vector inversely scaled by s.

Definition at line 395 of file Vector3.h.

TFSIMD_FORCE_INLINE Vector3 tf::operator/ ( const Vector3 v1,
const Vector3 v2 
)

Return the vector inversely scaled by s.

Definition at line 403 of file Vector3.h.

template<typename T >
bool tf::operator== ( const Stamped< T > &  a,
const Stamped< T > &  b 
)

Comparison Operator for Stamped datatypes.

Definition at line 75 of file transform_datatypes.h.

static bool tf::operator== ( const StampedTransform a,
const StampedTransform b 
)
inlinestatic

Comparison operator for StampedTransform.

Definition at line 99 of file transform_datatypes.h.

TFSIMD_FORCE_INLINE bool tf::operator== ( const Transform t1,
const Transform t2 
)

Test if two transforms have all elements equal.

Definition at line 243 of file Transform.h.

TFSIMD_FORCE_INLINE bool tf::operator== ( const Matrix3x3 m1,
const Matrix3x3 m2 
)

Equality operator between two matrices It will test all elements are equal.

Definition at line 640 of file Matrix3x3.h.

static void tf::pointMsgToTF ( const geometry_msgs::Point &  msg_v,
Point bt_v 
)
inlinestatic

convert Point msg to Point

Definition at line 221 of file transform_datatypes.h.

static void tf::pointStampedMsgToTF ( const geometry_msgs::PointStamped &  msg,
Stamped< Point > &  bt 
)
inlinestatic

convert PointStamped msg to Stamped<Point>

Definition at line 226 of file transform_datatypes.h.

static void tf::pointStampedTFToMsg ( const Stamped< Point > &  bt,
geometry_msgs::PointStamped &  msg 
)
inlinestatic

convert Stamped<Point> to PointStamped msg

Definition at line 229 of file transform_datatypes.h.

static void tf::pointTFToMsg ( const Point bt_v,
geometry_msgs::Point &  msg_v 
)
inlinestatic

convert Point to Point msg

Definition at line 223 of file transform_datatypes.h.

static void tf::poseMsgToTF ( const geometry_msgs::Pose &  msg,
Pose bt 
)
inlinestatic

convert Pose msg to Pose

Definition at line 248 of file transform_datatypes.h.

static void tf::poseStampedMsgToTF ( const geometry_msgs::PoseStamped &  msg,
Stamped< Pose > &  bt 
)
inlinestatic

convert PoseStamped msg to Stamped<Pose>

Definition at line 255 of file transform_datatypes.h.

static void tf::poseStampedTFToMsg ( const Stamped< Pose > &  bt,
geometry_msgs::PoseStamped &  msg 
)
inlinestatic

convert Stamped<Pose> to PoseStamped msg

Definition at line 258 of file transform_datatypes.h.

static void tf::poseTFToMsg ( const Pose bt,
geometry_msgs::Pose &  msg 
)
inlinestatic

convert Pose to Pose msg

Definition at line 251 of file transform_datatypes.h.

static void tf::quaternionMsgToTF ( const geometry_msgs::Quaternion &  msg,
Quaternion bt 
)
inlinestatic

convert Quaternion msg to Quaternion

Definition at line 105 of file transform_datatypes.h.

static void tf::quaternionStampedMsgToTF ( const geometry_msgs::QuaternionStamped &  msg,
Stamped< Quaternion > &  bt 
)
inlinestatic

convert QuaternionStamped msg to Stamped<Quaternion>

Definition at line 201 of file transform_datatypes.h.

static void tf::quaternionStampedTFToMsg ( const Stamped< Quaternion > &  bt,
geometry_msgs::QuaternionStamped &  msg 
)
inlinestatic

convert Stamped<Quaternion> to QuaternionStamped msg

Definition at line 204 of file transform_datatypes.h.

static void tf::quaternionTFToMsg ( const Quaternion bt,
geometry_msgs::Quaternion &  msg 
)
inlinestatic

convert Quaternion to Quaternion msg

Definition at line 115 of file transform_datatypes.h.

TFSIMD_FORCE_INLINE Vector3 tf::quatRotate ( const Quaternion rotation,
const Vector3 v 
)

Definition at line 436 of file Quaternion.h.

std::string tf::remap ( const std::string &  frame_id)

resolve names

Deprecated:
Use TransformListener::remap instead

Definition at line 36 of file transform_listener.cpp.

std::string tf::resolve ( const std::string &  prefix,
const std::string &  frame_name 
)

resolve tf names

Definition at line 159 of file tf.cpp.

TFSIMD_FORCE_INLINE Quaternion tf::shortestArcQuat ( const Vector3 v0,
const Vector3 v1 
)

Definition at line 444 of file Quaternion.h.

TFSIMD_FORCE_INLINE Quaternion tf::shortestArcQuatNormalize2 ( Vector3 v0,
Vector3 v1 
)

Definition at line 463 of file Quaternion.h.

TFSIMD_FORCE_INLINE Quaternion tf::slerp ( const Quaternion q1,
const Quaternion q2,
const tfScalar t 
)

Return the result of spherical linear interpolation betwen two quaternions.

Parameters
q1The first quaternion
q2The second quaternion
tThe ration between q1 and q2. t = 0 return q1, t=1 returns q2 Slerp assumes constant velocity between positions.

Definition at line 430 of file Quaternion.h.

std::string tf::strip_leading_slash ( const std::string &  frame_name)

strip a leading slash for

Definition at line 195 of file tf.cpp.

TFSIMD_FORCE_INLINE tfScalar tf::tfAngle ( const Vector3 v1,
const Vector3 v2 
)

Return the angle between two vectors.

Definition at line 433 of file Vector3.h.

TFSIMD_FORCE_INLINE Vector3 tf::tfCross ( const Vector3 v1,
const Vector3 v2 
)

Return the cross product of two vectors.

Definition at line 440 of file Vector3.h.

TFSIMD_FORCE_INLINE tfScalar tf::tfDistance ( const Vector3 v1,
const Vector3 v2 
)

Return the distance between two vectors.

Definition at line 426 of file Vector3.h.

TFSIMD_FORCE_INLINE tfScalar tf::tfDistance2 ( const Vector3 v1,
const Vector3 v2 
)

Return the distance squared between two vectors.

Definition at line 418 of file Vector3.h.

TFSIMD_FORCE_INLINE tfScalar tf::tfDot ( const Vector3 v1,
const Vector3 v2 
)

Return the dot product between two vectors.

Definition at line 410 of file Vector3.h.

TFSIMD_FORCE_INLINE void tf::tfPlaneSpace1 ( const Vector3 n,
Vector3 p,
Vector3 q 
)

Definition at line 658 of file Vector3.h.

TFSIMD_FORCE_INLINE void tf::tfSwapScalarEndian ( const tfScalar sourceVal,
tfScalar destVal 
)

tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization

Definition at line 623 of file Vector3.h.

TFSIMD_FORCE_INLINE void tf::tfSwapVector3Endian ( const Vector3 sourceVec,
Vector3 destVec 
)

tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization

Definition at line 637 of file Vector3.h.

TFSIMD_FORCE_INLINE tfScalar tf::tfTriple ( const Vector3 v1,
const Vector3 v2,
const Vector3 v3 
)

Definition at line 446 of file Vector3.h.

TFSIMD_FORCE_INLINE void tf::tfUnSwapVector3Endian ( Vector3 vector)

tfUnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization

Definition at line 647 of file Vector3.h.

static void tf::transformMsgToTF ( const geometry_msgs::Transform &  msg,
Transform bt 
)
inlinestatic

convert Transform msg to Transform

Definition at line 234 of file transform_datatypes.h.

static void tf::transformStampedMsgToTF ( const geometry_msgs::TransformStamped &  msg,
StampedTransform bt 
)
inlinestatic

convert TransformStamped msg to tf::StampedTransform

Definition at line 241 of file transform_datatypes.h.

static void tf::transformStampedTFToMsg ( const StampedTransform bt,
geometry_msgs::TransformStamped &  msg 
)
inlinestatic

convert tf::StampedTransform to TransformStamped msg

Definition at line 244 of file transform_datatypes.h.

static void tf::transformTFToMsg ( const Transform bt,
geometry_msgs::Transform &  msg 
)
inlinestatic

convert Transform to Transform msg

Definition at line 237 of file transform_datatypes.h.

static void tf::vector3MsgToTF ( const geometry_msgs::Vector3 msg_v,
Vector3 bt_v 
)
inlinestatic

convert Vector3 msg to Vector3

Definition at line 208 of file transform_datatypes.h.

static void tf::vector3StampedMsgToTF ( const geometry_msgs::Vector3Stamped &  msg,
Stamped< Vector3 > &  bt 
)
inlinestatic

convert Vector3Stamped msg to Stamped<Vector3>

Definition at line 213 of file transform_datatypes.h.

static void tf::vector3StampedTFToMsg ( const Stamped< Vector3 > &  bt,
geometry_msgs::Vector3Stamped &  msg 
)
inlinestatic

convert Stamped<Vector3> to Vector3Stamped msg

Definition at line 216 of file transform_datatypes.h.

static void tf::vector3TFToMsg ( const Vector3 bt_v,
geometry_msgs::Vector3 msg_v 
)
inlinestatic

convert Vector3 to Vector3 msg

Definition at line 210 of file transform_datatypes.h.

Variable Documentation

tf::tfVector4 tf::__attribute__
const double tf::QUATERNION_TOLERANCE = 0.1f
static

Definition at line 52 of file transform_datatypes.h.



tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Jun 10 2019 12:25:26