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...
struct  FrameGraph
struct  FrameGraphRequest_
struct  FrameGraphResponse_
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  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  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...
struct  tfMessage_
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  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...
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...
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...

Typedefs

typedef
filter_failure_reasons::FilterFailureReason 
FilterFailureReason
typedef
::tf::FrameGraphRequest_
< std::allocator< void > > 
FrameGraphRequest
typedef boost::shared_ptr
< ::tf::FrameGraphRequest
const > 
FrameGraphRequestConstPtr
typedef boost::shared_ptr
< ::tf::FrameGraphRequest
FrameGraphRequestPtr
typedef
::tf::FrameGraphResponse_
< std::allocator< void > > 
FrameGraphResponse
typedef boost::shared_ptr
< ::tf::FrameGraphResponse
const > 
FrameGraphResponseConstPtr
typedef boost::shared_ptr
< ::tf::FrameGraphResponse
FrameGraphResponsePtr
typedef btVector3 Point
 The transform library representation of a point(Position).
typedef btTransform Pose
 A representation of pose (A position and orientation).
typedef btQuaternion Quaternion
 A representaton of orientation or rotation depending on context.
typedef ::tf::tfMessage_
< std::allocator< void > > 
tfMessage
typedef boost::shared_ptr
< ::tf::tfMessage const > 
tfMessageConstPtr
typedef boost::shared_ptr
< ::tf::tfMessage
tfMessagePtr
typedef btTransform Transform
 A representation of a translation and rotation.
typedef btVector3 Vector3
 A representation of a translation.

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
void assertQuaternionValid (const geometry_msgs::Quaternion &q)
 Throw InvalidArgument if quaternion is malformed.
void assertQuaternionValid (const tf::Quaternion &q)
 Throw InvalidArgument if quaternion is malformed.
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
std::string getPrefixParam (ros::NodeHandle &nh)
 Get the tf_prefix from the parameter server.
static double getYaw (const geometry_msgs::Quaternion &msg_q)
 Helper function for getting yaw from a Quaternion message.
static double getYaw (const Quaternion &bt_q)
 Helper function for getting yaw from a Quaternion.
template<typename ContainerAllocator >
std::ostream & operator<< (std::ostream &s, const ::tf::tfMessage_< ContainerAllocator > &v)
static bool operator== (const StampedTransform &a, const StampedTransform &b)
 Comparison operator for StampedTransform.
template<typename T >
bool operator== (const Stamped< T > &a, const Stamped< T > &b)
 Comparison Operator for Stamped datatypes.
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
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
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

Definition at line 75 of file message_filter.h.

typedef ::tf::FrameGraphRequest_<std::allocator<void> > tf::FrameGraphRequest

Definition at line 84 of file FrameGraph.h.

typedef boost::shared_ptr< ::tf::FrameGraphRequest const> tf::FrameGraphRequestConstPtr

Definition at line 87 of file FrameGraph.h.

typedef boost::shared_ptr< ::tf::FrameGraphRequest> tf::FrameGraphRequestPtr

Definition at line 86 of file FrameGraph.h.

typedef ::tf::FrameGraphResponse_<std::allocator<void> > tf::FrameGraphResponse

Definition at line 164 of file FrameGraph.h.

typedef boost::shared_ptr< ::tf::FrameGraphResponse const> tf::FrameGraphResponseConstPtr

Definition at line 167 of file FrameGraph.h.

typedef boost::shared_ptr< ::tf::FrameGraphResponse> tf::FrameGraphResponsePtr

Definition at line 166 of file FrameGraph.h.

typedef btVector3 tf::Point

The transform library representation of a point(Position).

Definition at line 53 of file transform_datatypes.h.

typedef btTransform tf::Pose

A representation of pose (A position and orientation).

Definition at line 57 of file transform_datatypes.h.

typedef btQuaternion tf::Quaternion

A representaton of orientation or rotation depending on context.

Definition at line 49 of file transform_datatypes.h.

typedef ::tf::tfMessage_<std::allocator<void> > tf::tfMessage

Definition at line 141 of file tfMessage.h.

typedef boost::shared_ptr< ::tf::tfMessage const> tf::tfMessageConstPtr

Definition at line 144 of file tfMessage.h.

typedef boost::shared_ptr< ::tf::tfMessage> tf::tfMessagePtr

Definition at line 143 of file tfMessage.h.

typedef btTransform tf::Transform

A representation of a translation and rotation.

Definition at line 55 of file transform_datatypes.h.

typedef btVector3 tf::Vector3

A representation of a translation.

Todo:
differentiate?

Definition at line 51 of file transform_datatypes.h.


Enumeration Type Documentation

Enumerator:
NO_ERROR 
LOOKUP_ERROR 
CONNECTIVITY_ERROR 
EXTRAPOLATION_ERROR 

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

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

Throw InvalidArgument if quaternion is malformed.

Definition at line 486 of file tf.h.

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

Throw InvalidArgument if quaternion is malformed.

Definition at line 475 of file tf.h.

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

construct an Identity Quaternion

Returns:
The quaternion constructed

Definition at line 200 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:
roll The roll about the X axis
pitch The pitch about the Y axis
yaw The yaw about the Z axis
Returns:
The quaternion constructed

Definition at line 157 of file transform_datatypes.h.

static Quaternion tf::createQuaternionFromYaw ( double  yaw  )  [inline, static]

construct a Quaternion from yaw only

Parameters:
yaw The yaw about the Z axis
Returns:
The quaternion constructed

Definition at line 167 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:
roll The roll about the X axis
pitch The pitch about the Y axis
yaw The yaw about the Z axis
Returns:
The quaternion constructed

Definition at line 191 of file transform_datatypes.h.

static geometry_msgs::Quaternion tf::createQuaternionMsgFromYaw ( double  yaw  )  [inline, static]

construct a Quaternion Message from yaw only

Parameters:
yaw The yaw about the Z axis
Returns:
The quaternion constructed

Definition at line 177 of file transform_datatypes.h.

std::string tf::getPrefixParam ( ros::NodeHandle &  nh  )  [inline]

Get the tf_prefix from the parameter server.

Parameters:
nh The 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 geometry_msgs::Quaternion &  msg_q  )  [inline, static]

Helper function for getting yaw from a Quaternion message.

Definition at line 145 of file transform_datatypes.h.

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

Helper function for getting yaw from a Quaternion.

Definition at line 138 of file transform_datatypes.h.

template<typename ContainerAllocator >
std::ostream& tf::operator<< ( std::ostream &  s,
const ::tf::tfMessage_< ContainerAllocator > &  v 
) [inline]

Definition at line 148 of file tfMessage.h.

static bool tf::operator== ( const StampedTransform &  a,
const StampedTransform &  b 
) [inline, static]

Comparison operator for StampedTransform.

Definition at line 106 of file transform_datatypes.h.

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

Comparison Operator for Stamped datatypes.

Definition at line 82 of file transform_datatypes.h.

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

convert Point msg to Point

Definition at line 228 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 233 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 236 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 230 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 255 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 262 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 265 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 258 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 112 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 208 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 211 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 122 of file transform_datatypes.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 53 of file tf.cpp.

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

convert Transform msg to Transform

Definition at line 241 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 248 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 251 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 244 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 215 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 220 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 223 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 217 of file transform_datatypes.h.


Variable Documentation

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

Definition at line 59 of file transform_datatypes.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Fri Jan 11 09:09:56 2013