Classes | Public Types | Public Member Functions | Static Public Attributes | Private Types | Private Member Functions | Private Attributes | Friends
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

boost::signals2::connection _addTransformsChangedListener (boost::function< void(void)> callback)
 Add a callback that happens when a new transform has arrived.
std::string _allFramesAsDot (double current_time) const
 Backwards compatabilityA way to see what frames have been cached Useful for debugging.
std::string _allFramesAsDot () const
void _chainAsVector (const std::string &target_frame, ros::Time target_time, const std::string &source_frame, ros::Time source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
 Backwards compatabilityA way to see what frames are in a chain Useful for debugging.
bool _frameExists (const std::string &frame_id_str) const
 Check if a frame exists in the tree.
void _getFrameStrings (std::vector< std::string > &ids) const
 A way to get a std::vector of available frame ids.
int _getLatestCommonTime (CompactFrameID target_frame, CompactFrameID source_frame, ros::Time &time, std::string *error_string) const
bool _getParent (const std::string &frame_id, ros::Time time, std::string &parent) const
 Fill the parent of a frame.
CompactFrameID _lookupFrameNumber (const std::string &frameid_str) const
CompactFrameID _lookupOrInsertFrameNumber (const std::string &frameid_str)
void _removeTransformsChangedListener (boost::signals2::connection c)
CompactFrameID _validateFrameId (const char *function_name_arg, const std::string &frame_id) const
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 (double current_time) const
 A way to see what frames have been cached in yaml format Useful for debugging tools.
std::string allFramesAsYAML () const
 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 std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
 Test if a transform is possible.
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.
void clear ()
 Clear all data.
ros::Duration getCacheLength ()
 Get the duration over which this transformer will cache.
bool isUsingDedicatedThread () const
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.
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.
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.
void setUsingDedicatedThread (bool value)
virtual ~BufferCore (void)

Static Public Attributes

static const int DEFAULT_CACHE_TIME = 10
 The default amount of time to cache data in seconds.
static const uint32_t MAX_GRAPH_DEPTH = 1000UL
 Maximum graph search depth (deeper graphs will be assumed to have loops)

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
boost::signals2::signal< void(void)> 
TransformsChangedSignal
typedef std::vector
< TimeCacheInterfacePtr
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

std::string allFramesAsStringNoLock () const
 A way to see what frames have been cached Useful for debugging. Use this call internally.
TimeCacheInterfacePtr allocateFrame (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
TimeCacheInterfacePtr getFrame (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
template<typename F >
int walkToTopParent (F &f, ros::Time time, CompactFrameID target_id, CompactFrameID source_id, std::string *error_string, std::vector< CompactFrameID > *frame_chain) const
 Traverse the transform tree. If frame_chain is not NULL, store the traversed frame tree in vector frame_chain.
bool warnFrameId (const char *function_name_arg, const std::string &frame_id) const

Private Attributes

TransformsChangedSignal _transforms_changed_
 Signal which is fired whenever new transform data has arrived, from the thread the data arrived in.
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_
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_
bool using_dedicated_thread_

Friends

class TestBufferCore

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 88 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 327 of file buffer_core.h.

Definition at line 338 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 227 of file buffer_core.h.

typedef boost::signals2::signal<void(void)> tf2::BufferCore::TransformsChangedSignal [private]

Definition at line 359 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 320 of file buffer_core.h.

Definition at line 353 of file buffer_core.h.


Constructor & Destructor Documentation

Constructor

Parameters:
interpolatingWhether to interpolate, if this is false the closest value will be returned
cache_timeHow long to keep a history of transforms in nanoseconds

Definition at line 168 of file buffer_core.cpp.

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

Definition at line 179 of file buffer_core.cpp.


Member Function Documentation

boost::signals2::connection tf2::BufferCore::_addTransformsChangedListener ( boost::function< void(void)>  callback)

Add a callback that happens when a new transform has arrived.

Parameters:
callbackThe callback, of the form void func();
Returns:
A boost::signals2::connection object that can be used to remove this listener

Definition at line 1349 of file buffer_core.cpp.

std::string tf2::BufferCore::_allFramesAsDot ( double  current_time) const

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

Definition at line 1488 of file buffer_core.cpp.

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

Definition at line 1572 of file buffer_core.cpp.

void tf2::BufferCore::_chainAsVector ( const std::string &  target_frame,
ros::Time  target_time,
const std::string &  source_frame,
ros::Time  source_time,
const std::string &  fixed_frame,
std::vector< std::string > &  output 
) const

Backwards compatabilityA way to see what frames are in a chain Useful for debugging.

Definition at line 1577 of file buffer_core.cpp.

bool tf2::BufferCore::_frameExists ( const std::string &  frame_id_str) const

Check if a frame exists in the tree.

Parameters:
frame_id_strThe frame id in question

Definition at line 1362 of file buffer_core.cpp.

void tf2::BufferCore::_getFrameStrings ( std::vector< std::string > &  ids) const

A way to get a std::vector of available frame ids.

Definition at line 1386 of file buffer_core.cpp.

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

Definition at line 285 of file buffer_core.h.

bool tf2::BufferCore::_getParent ( const std::string &  frame_id,
ros::Time  time,
std::string &  parent 
) const

Fill the parent of a frame.

Parameters:
frame_idThe frame id of the frame in question
parentThe reference to the string to fill the parent Returns true unless "NO_PARENT"

Definition at line 1368 of file buffer_core.cpp.

CompactFrameID tf2::BufferCore::_lookupFrameNumber ( const std::string &  frameid_str) const [inline]

Definition at line 278 of file buffer_core.h.

CompactFrameID tf2::BufferCore::_lookupOrInsertFrameNumber ( const std::string &  frameid_str) [inline]

Definition at line 281 of file buffer_core.h.

void tf2::BufferCore::_removeTransformsChangedListener ( boost::signals2::connection  c)

Definition at line 1355 of file buffer_core.cpp.

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

Definition at line 290 of file buffer_core.h.

Internal use only.

Definition at line 1226 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 1266 of file buffer_core.cpp.

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

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

Definition at line 948 of file buffer_core.cpp.

std::string tf2::BufferCore::allFramesAsStringNoLock ( ) const [private]

A way to see what frames have been cached Useful for debugging. Use this call internally.

regular transforms

Definition at line 954 of file buffer_core.cpp.

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

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

Definition at line 1164 of file buffer_core.cpp.

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

Backwards compatibility for #84

Definition at line 1221 of file buffer_core.cpp.

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

Definition at line 287 of file buffer_core.cpp.

Internal use only.

Definition at line 1335 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

Test if a transform is possible.

Parameters:
target_frameThe frame into which to transform
source_frameThe frame from which to transform
timeThe time at which to transform
error_msgA 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 799 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_frameThe frame into which to transform
target_timeThe time into which to transform
source_frameThe frame from which to transform
source_timeThe time from which to transform
fixed_frameThe frame in which to treat the transform as constant in time
error_msgA 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 838 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 792 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 755 of file buffer_core.cpp.

Clear all data.

Definition at line 184 of file buffer_core.cpp.

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

Definition at line 937 of file buffer_core.cpp.

Get the duration over which this transformer will cache.

Definition at line 295 of file buffer_core.h.

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

Parameters:
frame_numberThe 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

Definition at line 885 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.

Definition at line 995 of file buffer_core.cpp.

bool tf2::BufferCore::isUsingDedicatedThread ( ) const [inline]

Definition at line 245 of file buffer_core.h.

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 895 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 925 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 908 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_frameThe frame to which data should be transformed
source_frameThe frame where the data originated
timeThe 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 591 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_frameThe frame to which data should be transformed
target_timeThe time to which the data should be transformed. (0 will get the latest)
source_frameThe frame where the data originated
source_timeThe time at which the source_frame should be evaluated. (0 will get the latest)
fixed_frameThe 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 647 of file buffer_core.cpp.

Internal use only.

Definition at line 1252 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:
transformThe transform to store
authorityThe source of the information for this transform
is_staticRecord 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 201 of file buffer_core.cpp.

void tf2::BufferCore::setUsingDedicatedThread ( bool  value) [inline]

Definition at line 243 of file buffer_core.h.

Definition at line 1405 of file buffer_core.cpp.

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

Definition at line 141 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 [private]

Definition at line 309 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,
std::vector< CompactFrameID > *  frame_chain 
) const [private]

Traverse the transform tree. If frame_chain is not NULL, store the traversed frame tree in vector frame_chain.

Definition at line 315 of file buffer_core.cpp.

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

Definition at line 120 of file buffer_core.cpp.


Friends And Related Function Documentation

friend class TestBufferCore [friend]

Definition at line 417 of file buffer_core.h.


Member Data Documentation

Signal which is fired whenever new transform data has arrived, from the thread the data arrived in.

Definition at line 364 of file buffer_core.h.

How long to cache transform history.

Definition at line 336 of file buffer_core.h.

const int tf2::BufferCore::DEFAULT_CACHE_TIME = 10 [static]

The default amount of time to cache data in seconds.

Definition at line 92 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 332 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 324 of file buffer_core.h.

Definition at line 328 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 330 of file buffer_core.h.

Definition at line 321 of file buffer_core.h.

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

Maximum graph search depth (deeper graphs will be assumed to have loops)

Definition at line 93 of file buffer_core.h.

Definition at line 339 of file buffer_core.h.

Definition at line 340 of file buffer_core.h.

Definition at line 341 of file buffer_core.h.

Definition at line 354 of file buffer_core.h.

Definition at line 356 of file buffer_core.h.

Definition at line 355 of file buffer_core.h.

Definition at line 414 of file buffer_core.h.


The documentation for this class was generated from the following files:


tf2
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Thu Jun 6 2019 20:22:56