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

Namespaces

namespace  filter_failure_reasons

Classes

class  ConnectivityException
 An exception class to notify of no connection. More...
class  ExtrapolationException
 An exception class to notify that the requested value would have required extrapolation beyond current limits. More...
class  InvalidArgument
 An exception class to notify that one of the arguments is invalid. More...
class  LookupException
 An exception class to notify of bad frame number. More...
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...
class  TransformException
 A base class for all tf exceptions This inherits from ros::exception which inherits from std::runtime_exception. 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...
struct  Vector3DoubleData
struct  Vector3FloatData

Typedefs

typedef uint32_t CompactFrameID
typedef
filter_failure_reasons::FilterFailureReason 
FilterFailureReason
typedef std::pair< ros::Time,
CompactFrameID
P_TimeAndFrameID
typedef tf::Vector3 Point
typedef tf::Transform Pose

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
TFSIMD_FORCE_INLINE tfScalar angle (const Quaternion &q1, const Quaternion &q2)
 Return the ***half*** angle between two quaternions.
TFSIMD_FORCE_INLINE tfScalar angleShortestPath (const Quaternion &q1, const Quaternion &q2)
 Return the shortest angle between two quaternions.
void assertQuaternionValid (const tf::Quaternion &q)
 Throw InvalidArgument if quaternion is malformed.
void assertQuaternionValid (const geometry_msgs::Quaternion &q)
 Throw InvalidArgument if quaternion is malformed.
 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.
static tf::Quaternion createIdentityQuaternion ()
 construct an Identity Quaternion
static tf::Quaternion createQuaternionFromRPY (double roll, double pitch, double yaw)
 construct a Quaternion from Fixed angles
static Quaternion createQuaternionFromYaw (double yaw)
 construct a Quaternion from yaw only
static geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw (double roll, double pitch, double yaw)
 construct a Quaternion Message from Fixed angles
static geometry_msgs::Quaternion createQuaternionMsgFromYaw (double yaw)
 construct a Quaternion Message from yaw only
TFSIMD_FORCE_INLINE tfScalar dot (const Quaternion &q1, const Quaternion &q2)
 Calculate the dot product between two quaternions.
std::string getPrefixParam (ros::NodeHandle &nh)
 Get the tf_prefix from the parameter server.
static double getYaw (const Quaternion &bt_q)
 Helper function for getting yaw from a Quaternion.
static double getYaw (const geometry_msgs::Quaternion &msg_q)
 Helper function for getting yaw from a Quaternion message.
TFSIMD_FORCE_INLINE Quaternion inverse (const Quaternion &q)
 Return the inverse of a quaternion.
TFSIMD_FORCE_INLINE tfScalar length (const Quaternion &q)
 Return the length of a quaternion.
TFSIMD_FORCE_INLINE Vector3 lerp (const Vector3 &v1, const Vector3 &v2, const tfScalar &t)
 Return the linear interpolation between two vectors.
TFSIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v1, const Vector3 &v2)
 Return the elementwise product of two vectors.
TFSIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q1, const Quaternion &q2)
 Return the product of two quaternions.
TFSIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q, const Vector3 &w)
TFSIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v, const tfScalar &s)
 Return the vector scaled by s.
TFSIMD_FORCE_INLINE Quaternion operator* (const Vector3 &w, const Quaternion &q)
TFSIMD_FORCE_INLINE Vector3 operator* (const tfScalar &s, const Vector3 &v)
 Return the vector scaled by s.
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)
TFSIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q)
 Return the negative of a quaternion.
TFSIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v1, const Vector3 &v2)
 Return the difference between two vectors.
TFSIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v)
 Return the negative of the vector.
TFSIMD_FORCE_INLINE Vector3 operator/ (const Vector3 &v, const tfScalar &s)
 Return the vector inversely scaled by s.
TFSIMD_FORCE_INLINE Vector3 operator/ (const Vector3 &v1, const Vector3 &v2)
 Return the vector inversely scaled by s.
template<typename T >
bool operator== (const Stamped< T > &a, const Stamped< T > &b)
 Comparison Operator for Stamped datatypes.
static bool operator== (const StampedTransform &a, const StampedTransform &b)
 Comparison operator for StampedTransform.
TFSIMD_FORCE_INLINE bool operator== (const Transform &t1, const Transform &t2)
 Test if two transforms have all elements equal.
TFSIMD_FORCE_INLINE bool operator== (const Matrix3x3 &m1, const Matrix3x3 &m2)
 Equality operator between two matrices It will test all elements are equal.
static void pointMsgToTF (const geometry_msgs::Point &msg_v, Point &bt_v)
 convert Point msg to Point
static void pointStampedMsgToTF (const geometry_msgs::PointStamped &msg, Stamped< Point > &bt)
 convert PointStamped msg to Stamped<Point>
static void pointStampedTFToMsg (const Stamped< Point > &bt, geometry_msgs::PointStamped &msg)
 convert Stamped<Point> to PointStamped msg
static void pointTFToMsg (const Point &bt_v, geometry_msgs::Point &msg_v)
 convert Point to Point msg
static void poseMsgToTF (const geometry_msgs::Pose &msg, Pose &bt)
 convert Pose msg to Pose
static void poseStampedMsgToTF (const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
 convert PoseStamped msg to Stamped<Pose>
static void poseStampedTFToMsg (const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
 convert Stamped<Pose> to PoseStamped msg
static void poseTFToMsg (const Pose &bt, geometry_msgs::Pose &msg)
 convert Pose to Pose msg
static void quaternionMsgToTF (const geometry_msgs::Quaternion &msg, Quaternion &bt)
 convert Quaternion msg to Quaternion
static void quaternionStampedMsgToTF (const geometry_msgs::QuaternionStamped &msg, Stamped< Quaternion > &bt)
 convert QuaternionStamped msg to Stamped<Quaternion>
static void quaternionStampedTFToMsg (const Stamped< Quaternion > &bt, geometry_msgs::QuaternionStamped &msg)
 convert Stamped<Quaternion> to QuaternionStamped msg
static void quaternionTFToMsg (const Quaternion &bt, geometry_msgs::Quaternion &msg)
 convert Quaternion to Quaternion msg
TFSIMD_FORCE_INLINE Vector3 quatRotate (const Quaternion &rotation, const Vector3 &v)
std::string remap (const std::string &frame_id) __attribute__((deprecated))
 resolve names
std::string resolve (const std::string &prefix, const std::string &frame_name)
 resolve tf names
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.
TFSIMD_FORCE_INLINE tfScalar tfAngle (const Vector3 &v1, const Vector3 &v2)
 Return the angle between two vectors.
TFSIMD_FORCE_INLINE Vector3 tfCross (const Vector3 &v1, const Vector3 &v2)
 Return the cross product of two vectors.
TFSIMD_FORCE_INLINE tfScalar tfDistance (const Vector3 &v1, const Vector3 &v2)
 Return the distance between two vectors.
TFSIMD_FORCE_INLINE tfScalar tfDistance2 (const Vector3 &v1, const Vector3 &v2)
 Return the distance squared between two vectors.
TFSIMD_FORCE_INLINE tfScalar tfDot (const Vector3 &v1, const Vector3 &v2)
 Return the dot product between two vectors.
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
TFSIMD_FORCE_INLINE void tfSwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec)
 tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization
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
static void transformMsgToTF (const geometry_msgs::Transform &msg, Transform &bt)
 convert Transform msg to Transform
static void transformStampedMsgToTF (const geometry_msgs::TransformStamped &msg, StampedTransform &bt)
 convert TransformStamped msg to tf::StampedTransform
static void transformStampedTFToMsg (const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
 convert tf::StampedTransform to TransformStamped msg
static void transformTFToMsg (const Transform &bt, geometry_msgs::Transform &msg)
 convert Transform to Transform msg
static void vector3MsgToTF (const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v)
 convert Vector3 msg to Vector3
static void vector3StampedMsgToTF (const geometry_msgs::Vector3Stamped &msg, Stamped< Vector3 > &bt)
 convert Vector3Stamped msg to Stamped<Vector3>
static void vector3StampedTFToMsg (const Stamped< Vector3 > &bt, geometry_msgs::Vector3Stamped &msg)
 convert Stamped<Vector3> to Vector3Stamped msg
static void vector3TFToMsg (const Vector3 &bt_v, geometry_msgs::Vector3 &msg_v)
 convert Vector3 to Vector3 msg

Variables

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 75 of file message_filter.h.

Definition at line 51 of file time_cache.h.

typedef tf::Vector3 tf::Point

Definition at line 49 of file transform_datatypes.h.

Definition at line 50 of file transform_datatypes.h.


Enumeration Type Documentation

Enumerator:
NO_ERROR 
LOOKUP_ERROR 
CONNECTIVITY_ERROR 
EXTRAPOLATION_ERROR 

Definition at line 57 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 55 of file tf.h.

TFSIMD_FORCE_INLINE tfScalar tf::angle ( const Quaternion &  q1,
const Quaternion &  q2 
)

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

Definition at line 435 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 442 of file Quaternion.h.

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

Throw InvalidArgument if quaternion is malformed.

Definition at line 492 of file tf.h.

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

Throw InvalidArgument if quaternion is malformed.

Definition at line 503 of file tf.h.

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.

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.

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

No initialization constructor

Constructor from btVector3

Assign from a btVector3

Constructor from scalars

Parameters:
xX value
yY value
zZ value

Return a btVector3

Add a vector to this one

Parameters:
Thevector to add to this one

Sutfract a vector from this one

Parameters:
Thevector to sutfract

Scale the vector

Parameters:
sScale factor

Inversely scale the vector

Parameters:
sScale factor to divide by

Return the dot product

Parameters:
vThe other vector in the dot product

Return the length of the vector squared

Return the length of the vector

Return the distance squared between the ends of this and another vector This is symantically treating the vector like a point

Return the distance between the ends of this and another vector This is symantically treating the vector like a point

Normalize this vector x^2 + y^2 + z^2 = 1

Return a normalized version of this vector

Rotate this vector

Parameters:
wAxisThe axis to rotate about
angleThe angle to rotate by

Return the angle between this and another vector

Parameters:
vThe other vector

Return a vector will the absolute values of each element

Return the cross product between this and another vector

Parameters:
vThe other vector

Return the axis with the smallest value Note return values are 0,1,2 for x, y, or z

Return the axis with the largest value Note return values are 0,1,2 for x, y, or z

Return the linear interpolation between this and another vector

Parameters:
vThe other vector
tThe ration of this to v (t = 0 => return this, t=1 => return other)

Elementwise multiply this vector by the other

Parameters:
vThe other vector

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 each element to the max of the current values and the values of another Vector3

Parameters:
otherThe other Vector3 to compare with

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

Parameters:
otherThe other Vector3 to compare with

No initialization constructor

Constructor from btVector3

Assign from a btVector3

Constructor from scalars

Parameters:
xX value
yY value
zZ value

Return a btVector3

Add a vector to this one

Parameters:
Thevector to add to this one

Sutfract a vector from this one

Parameters:
Thevector to sutfract

Scale the vector

Parameters:
sScale factor

Inversely scale the vector

Parameters:
sScale factor to divide by

Return the dot product

Parameters:
vThe other vector in the dot product

Return the length of the vector squared

Return the length of the vector

Return the distance squared between the ends of this and another vector This is symantically treating the vector like a point

Return the distance between the ends of this and another vector This is symantically treating the vector like a point

Normalize this vector x^2 + y^2 + z^2 = 1

Return a normalized version of this vector

Rotate this vector

Parameters:
wAxisThe axis to rotate about
angleThe angle to rotate by

Return the angle between this and another vector

Parameters:
vThe other vector

Return a vector will the absolute values of each element

Return the cross product between this and another vector

Parameters:
vThe other vector

Return the axis with the smallest value Note return values are 0,1,2 for x, y, or z

Return the axis with the largest value Note return values are 0,1,2 for x, y, or z

Return the linear interpolation between this and another vector

Parameters:
vThe other vector
tThe ration of this to v (t = 0 => return this, t=1 => return other)

Elementwise multiply this vector by the other

Parameters:
vThe other vector

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 each element to the max of the current values and the values of another Vector3

Parameters:
otherThe other Vector3 to compare with

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

Parameters:
otherThe other Vector3 to compare with

Definition at line 34 of file QuadWord.h.

static tf::Quaternion tf::createIdentityQuaternion ( ) [inline, static]

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 
) [inline, static]

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) [inline, static]

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 
) [inline, static]

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) [inline, static]

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 420 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 51 of file transform_listener.h.

static double tf::getYaw ( const Quaternion &  bt_q) [inline, static]

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) [inline, static]

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 449 of file Quaternion.h.

TFSIMD_FORCE_INLINE tfScalar tf::length ( const Quaternion &  q)

Return the length of a quaternion.

Definition at line 428 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 481 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 386 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 393 of file Quaternion.h.

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

Definition at line 401 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 406 of file Vector3.h.

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

Definition at line 410 of file Quaternion.h.

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

Return the vector scaled by s.

Definition at line 413 of file Vector3.h.

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

Definition at line 628 of file Matrix3x3.h.

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

Definition at line 635 of file Matrix3x3.h.

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

Definition at line 641 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 379 of file Vector3.h.

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

Return the negative of a quaternion.

Definition at line 384 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 393 of file Vector3.h.

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

Return the negative of the vector.

Definition at line 399 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 420 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 428 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 
) [inline, static]

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 266 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 666 of file Matrix3x3.h.

static void tf::pointMsgToTF ( const geometry_msgs::Point &  msg_v,
Point &  bt_v 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 466 of file Quaternion.h.

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

resolve names

Deprecated:
Use TransformListener::remap instead

Definition at line 39 of file transform_listener.cpp.

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

resolve tf names

Definition at line 161 of file tf.cpp.

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

Definition at line 474 of file Quaternion.h.

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

Definition at line 493 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 460 of file Quaternion.h.

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

Return the angle between two vectors.

Definition at line 458 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 465 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 451 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 443 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 435 of file Vector3.h.

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

Definition at line 683 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 648 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 662 of file Vector3.h.

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

Definition at line 471 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 672 of file Vector3.h.

static void tf::transformMsgToTF ( const geometry_msgs::Transform &  msg,
Transform &  bt 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

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 
) [inline, static]

convert Vector3 to Vector3 msg

Definition at line 210 of file transform_datatypes.h.


Variable Documentation

const double tf::QUATERNION_TOLERANCE = 0.1f [static]

Definition at line 52 of file transform_datatypes.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Aug 22 2013 11:29:02