tf2::BufferCore Class Reference

A Class which provides coordinate transforms between any two frames in a system. More...

#include <buffer_core.h>

List of all members.

Classes

struct  RemoveRequestByCallback
struct  RemoveRequestByID
struct  TransformableRequest

Public Types

typedef boost::function< void(TransformableRequestHandle
request_handle, const
std::string &target_frame,
const std::string
&source_frame, ros::Time time,
TransformableResult result)> 
TransformableCallback

Public Member Functions

TransformableCallbackHandle addTransformableCallback (const TransformableCallback &cb)
 Internal use only.
TransformableRequestHandle addTransformableRequest (TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time)
 Internal use only.
std::string allFramesAsString () const
 A way to see what frames have been cached Useful for debugging.
std::string allFramesAsYAML () const
 A way to see what frames have been cached in yaml format Useful for debugging tools.
 BufferCore (ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
void cancelTransformableRequest (TransformableRequestHandle handle)
 Internal use only.
bool canTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, std::string *error_msg=NULL) const
 Test if a transform is possible.
bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
 Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point.
void clear ()
 Clear all data.
geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame) const
 Get the transform between two frames by frame ID assuming fixed frame.
geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
 Get the transform between two frames by frame ID.
void removeTransformableCallback (TransformableCallbackHandle handle)
 Internal use only.
bool setTransform (const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
 Add transform information to the tf data structure.
virtual ~BufferCore (void)

Static Public Attributes

static const double DEFAULT_CACHE_TIME = 10.0
 The default amount of time to cache data in seconds.
static const int64_t DEFAULT_MAX_EXTRAPOLATION_DISTANCE = 0ULL
 The default amount of time to extrapolate.
static const uint32_t MAX_GRAPH_DEPTH = 1000UL
 The default amount of time to cache data in seconds.

Private Types

typedef boost::unordered_map
< std::string, CompactFrameID
M_StringToCompactFrameID
 A map from string frame ids to CompactFrameID.
typedef boost::unordered_map
< TransformableCallbackHandle,
TransformableCallback
M_TransformableCallback
typedef std::vector
< TimeCacheInterface * > 
V_TimeCacheInterface
 The pointers to potential frames that the tree can be made of. The frames will be dynamically allocated at run time when set the first time.
typedef std::vector
< TransformableRequest
V_TransformableRequest

Private Member Functions

TimeCacheInterfaceallocateFrame (CompactFrameID cfid, bool is_static)
bool canTransformInternal (CompactFrameID target_id, CompactFrameID source_id, const ros::Time &time, std::string *error_msg) const
bool canTransformNoLock (CompactFrameID target_id, CompactFrameID source_id, const ros::Time &time, std::string *error_msg) const
void createConnectivityErrorString (CompactFrameID source_frame, CompactFrameID target_frame, std::string *out) const
TimeCacheInterfacegetFrame (CompactFrameID c_frame_id) const
 An accessor to get a frame, which will throw an exception if the frame is no there.
int getLatestCommonTime (CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
 Return the latest rostime which is common across the spanning set zero if fails to cross.
CompactFrameID lookupFrameNumber (const std::string &frameid_str) const
 String to number for frame lookup with dynamic allocation of new frames.
const std::string & lookupFrameString (CompactFrameID frame_id_num) const
 Number to string frame lookup may throw LookupException if number invalid.
CompactFrameID lookupOrInsertFrameNumber (const std::string &frameid_str)
 String to number for frame lookup with dynamic allocation of new frames.
void testTransformableRequests ()
CompactFrameID validateFrameId (const char *function_name_arg, const std::string &frame_id) const
template<typename F >
int walkToTopParent (F &f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string *error_string) const
bool warnFrameId (const char *function_name_arg, const std::string &frame_id) const

Private Attributes

ros::Duration cache_time_
 How long to cache transform history.
std::map< CompactFrameID,
std::string > 
frame_authority_
 A map to lookup the most recent authority for a given frame.
boost::mutex frame_mutex_
 A mutex to protect testing and allocating new frames on the above vector.
M_StringToCompactFrameID frameIDs_
std::vector< std::string > frameIDs_reverse
 A map from CompactFrameID frame_id_numbers to string for debugging and output.
V_TimeCacheInterface frames_
std::vector< P_TimeAndFrameIDlct_cache_
M_TransformableCallback transformable_callbacks_
uint32_t transformable_callbacks_counter_
boost::mutex transformable_callbacks_mutex_
V_TransformableRequest transformable_requests_
uint64_t transformable_requests_counter_
boost::mutex transformable_requests_mutex_

Detailed Description

A Class which provides coordinate transforms between any two frames in a system.

This class provides a simple interface to allow recording and lookup of relationships between arbitrary frames of the system.

libTF assumes that there is a tree of coordinate frame transforms which define the relationship between all coordinate frames. For example your typical robot would have a transform from global to real world. And then from base to hand, and from base to head. But Base to Hand really is composed of base to shoulder to elbow to wrist to hand. libTF is designed to take care of all the intermediate steps for you.

Internal Representation libTF will store frames with the parameters necessary for generating the transform into that frame from it's parent and a reference to the parent frame. Frames are designated using an std::string 0 is a frame without a parent (the top of a tree) The positions of frames over time must be pushed in.

All function calls which pass frame ids can potentially throw the exception tf::LookupException

Definition at line 76 of file buffer_core.h.


Member Typedef Documentation

typedef boost::unordered_map<std::string, CompactFrameID> tf2::BufferCore::M_StringToCompactFrameID [private]

A map from string frame ids to CompactFrameID.

Definition at line 237 of file buffer_core.h.

Definition at line 250 of file buffer_core.h.

typedef boost::function<void(TransformableRequestHandle request_handle, const std::string& target_frame, const std::string& source_frame, ros::Time time, TransformableResult result)> tf2::BufferCore::TransformableCallback

Definition at line 212 of file buffer_core.h.

The pointers to potential frames that the tree can be made of. The frames will be dynamically allocated at run time when set the first time.

Definition at line 230 of file buffer_core.h.

Definition at line 265 of file buffer_core.h.


Constructor & Destructor Documentation

tf2::BufferCore::BufferCore ( ros::Duration  cache_time_ = ros::Duration(DEFAULT_CACHE_TIME)  ) 

Constructor

Parameters:
interpolating Whether to interpolate, if this is false the closest value will be returned
cache_time How long to keep a history of transforms in nanoseconds

Definition at line 163 of file buffer_core.cpp.

tf2::BufferCore::~BufferCore ( void   )  [virtual]

Definition at line 173 of file buffer_core.cpp.


Member Function Documentation

TransformableCallbackHandle tf2::BufferCore::addTransformableCallback ( const TransformableCallback cb  ) 

Internal use only.

Definition at line 1017 of file buffer_core.cpp.

TransformableRequestHandle tf2::BufferCore::addTransformableRequest ( TransformableCallbackHandle  handle,
const std::string &  target_frame,
const std::string &  source_frame,
ros::Time  time 
)

Internal use only.

Definition at line 1057 of file buffer_core.cpp.

std::string tf2::BufferCore::allFramesAsString (  )  const

A way to see what frames have been cached Useful for debugging.

regular transforms

Definition at line 758 of file buffer_core.cpp.

std::string tf2::BufferCore::allFramesAsYAML (  )  const

A way to see what frames have been cached in yaml format Useful for debugging tools.

Definition at line 964 of file buffer_core.cpp.

TimeCacheInterface * tf2::BufferCore::allocateFrame ( CompactFrameID  cfid,
bool  is_static 
) [private]

Definition at line 267 of file buffer_core.cpp.

void tf2::BufferCore::cancelTransformableRequest ( TransformableRequestHandle  handle  ) 

Internal use only.

Definition at line 1126 of file buffer_core.cpp.

bool tf2::BufferCore::canTransform ( const std::string &  target_frame,
const ros::Time &  target_time,
const std::string &  source_frame,
const ros::Time &  source_time,
const std::string &  fixed_frame,
std::string *  error_msg = NULL 
) const

Test if a transform is possible.

Parameters:
target_frame The frame into which to transform
target_time The time into which to transform
source_frame The frame from which to transform
source_time The time from which to transform
fixed_frame The frame in which to treat the transform as constant in time
error_msg A pointer to a string which will be filled with why the transform failed, if not NULL
Returns:
True if the transform is possible, false otherwise

Definition at line 679 of file buffer_core.cpp.

bool tf2::BufferCore::canTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time &  time,
std::string *  error_msg = NULL 
) const

Lookup the twist of the tracking_frame with respect to the observation frame in the reference_frame using the reference point.

Parameters:
tracking_frame The frame to track
observation_frame The frame from which to measure the twist
reference_frame The reference frame in which to express the twist
reference_point The reference point with which to express the twist
reference_point_frame The frame_id in which the reference point is expressed
time The time at which to get the velocity
duration The period over which to average
Returns:
twist The twist output

This will compute the average velocity on the interval (time - duration/2, time+duration/2). If that is too close to the most recent reading, in which case it will shift the interval up to duration/2 to prevent extrapolation.

Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException

New in geometry 1.1 lookup the twist of the tracking frame with respect to the observational frame This is a simplified version of lookupTwist with it assumed that the reference point is the origin of the tracking frame, and the reference frame is the observation frame.

Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException

New in geometry 1.1 Test if a transform is possible

Parameters:
target_frame The frame into which to transform
source_frame The frame from which to transform
time The time at which to transform
error_msg A pointer to a string which will be filled with why the transform failed, if not NULL
Returns:
True if the transform is possible, false otherwise

Definition at line 663 of file buffer_core.cpp.

bool tf2::BufferCore::canTransformInternal ( CompactFrameID  target_id,
CompactFrameID  source_id,
const ros::Time &  time,
std::string *  error_msg 
) const [private]

Definition at line 656 of file buffer_core.cpp.

bool tf2::BufferCore::canTransformNoLock ( CompactFrameID  target_id,
CompactFrameID  source_id,
const ros::Time &  time,
std::string *  error_msg 
) const [private]

Definition at line 639 of file buffer_core.cpp.

void tf2::BufferCore::clear (  ) 

Clear all data.

Definition at line 178 of file buffer_core.cpp.

void tf2::BufferCore::createConnectivityErrorString ( CompactFrameID  source_frame,
CompactFrameID  target_frame,
std::string *  out 
) const [private]

Definition at line 747 of file buffer_core.cpp.

tf2::TimeCacheInterface * tf2::BufferCore::getFrame ( CompactFrameID  c_frame_id  )  const [private]

An accessor to get a frame, which will throw an exception if the frame is no there.

Parameters:
frame_number The frameID of the desired Reference Frame

This is an internal function which will get the pointer to the frame associated with the frame id Possible Exception: tf::LookupException

Todo:
check larger values too

Definition at line 694 of file buffer_core.cpp.

int tf2::BufferCore::getLatestCommonTime ( CompactFrameID  target_frame,
CompactFrameID  source_frame,
ros::Time &  time,
std::string *  error_string 
) const [private]

Return the latest rostime which is common across the spanning set zero if fails to cross.

Todo:
review was now();

Definition at line 802 of file buffer_core.cpp.

CompactFrameID tf2::BufferCore::lookupFrameNumber ( const std::string &  frameid_str  )  const [private]

String to number for frame lookup with dynamic allocation of new frames.

Definition at line 704 of file buffer_core.cpp.

const std::string & tf2::BufferCore::lookupFrameString ( CompactFrameID  frame_id_num  )  const [private]

Number to string frame lookup may throw LookupException if number invalid.

Definition at line 735 of file buffer_core.cpp.

CompactFrameID tf2::BufferCore::lookupOrInsertFrameNumber ( const std::string &  frameid_str  )  [private]

String to number for frame lookup with dynamic allocation of new frames.

Definition at line 718 of file buffer_core.cpp.

geometry_msgs::TransformStamped tf2::BufferCore::lookupTransform ( const std::string &  target_frame,
const ros::Time &  target_time,
const std::string &  source_frame,
const ros::Time &  source_time,
const std::string &  fixed_frame 
) const

Get the transform between two frames by frame ID assuming fixed frame.

Parameters:
target_frame The frame to which data should be transformed
target_time The time to which the data should be transformed. (0 will get the latest)
source_frame The frame where the data originated
source_time The time at which the source_frame should be evaluated. (0 will get the latest)
fixed_frame The frame in which to assume the transform is constant in time.
Returns:
The transform between the frames

Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException

Definition at line 531 of file buffer_core.cpp.

geometry_msgs::TransformStamped tf2::BufferCore::lookupTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time &  time 
) const

Get the transform between two frames by frame ID.

Parameters:
target_frame The frame to which data should be transformed
source_frame The frame where the data originated
time The time at which the value of the transform is desired. (0 will get the latest)
Returns:
The transform between the frames

Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException

Definition at line 497 of file buffer_core.cpp.

void tf2::BufferCore::removeTransformableCallback ( TransformableCallbackHandle  handle  ) 

Internal use only.

Definition at line 1043 of file buffer_core.cpp.

bool tf2::BufferCore::setTransform ( const geometry_msgs::TransformStamped &  transform,
const std::string &  authority,
bool  is_static = false 
)

Add transform information to the tf data structure.

Parameters:
transform The transform to store
authority The source of the information for this transform
is_static Record this transform as a static transform. It will be good across all time. (This cannot be changed after the first call.)
Returns:
True unless an error occured

Definition at line 194 of file buffer_core.cpp.

void tf2::BufferCore::testTransformableRequests (  )  [private]

Definition at line 1137 of file buffer_core.cpp.

CompactFrameID tf2::BufferCore::validateFrameId ( const char *  function_name_arg,
const std::string &  frame_id 
) const [private]

Definition at line 136 of file buffer_core.cpp.

template<typename F >
int tf2::BufferCore::walkToTopParent ( F &  f,
ros::Time  time,
CompactFrameID  target_id,
CompactFrameID  source_id,
std::string *  error_string 
) const [inline, private]

Definition at line 289 of file buffer_core.cpp.

bool tf2::BufferCore::warnFrameId ( const char *  function_name_arg,
const std::string &  frame_id 
) const [private]

Definition at line 115 of file buffer_core.cpp.


Member Data Documentation

ros::Duration tf2::BufferCore::cache_time_ [private]

How long to cache transform history.

Definition at line 246 of file buffer_core.h.

const double tf2::BufferCore::DEFAULT_CACHE_TIME = 10.0 [static]

The default amount of time to cache data in seconds.

Definition at line 80 of file buffer_core.h.

The default amount of time to extrapolate.

Definition at line 82 of file buffer_core.h.

std::map<CompactFrameID, std::string> tf2::BufferCore::frame_authority_ [private]

A map to lookup the most recent authority for a given frame.

Definition at line 242 of file buffer_core.h.

boost::mutex tf2::BufferCore::frame_mutex_ [mutable, private]

A mutex to protect testing and allocating new frames on the above vector.

Definition at line 234 of file buffer_core.h.

Definition at line 238 of file buffer_core.h.

std::vector<std::string> tf2::BufferCore::frameIDs_reverse [private]

A map from CompactFrameID frame_id_numbers to string for debugging and output.

Definition at line 240 of file buffer_core.h.

Definition at line 231 of file buffer_core.h.

std::vector<P_TimeAndFrameID> tf2::BufferCore::lct_cache_ [mutable, private]

Definition at line 248 of file buffer_core.h.

const uint32_t tf2::BufferCore::MAX_GRAPH_DEPTH = 1000UL [static]

The default amount of time to cache data in seconds.

Definition at line 81 of file buffer_core.h.

Definition at line 251 of file buffer_core.h.

Definition at line 252 of file buffer_core.h.

Definition at line 253 of file buffer_core.h.

Definition at line 266 of file buffer_core.h.

Definition at line 268 of file buffer_core.h.

Definition at line 267 of file buffer_core.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


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