Public Member Functions | Private Member Functions | Private Attributes | List of all members
tf2_ros::Buffer Class Reference

Standard implementation of the tf2_ros::BufferInterface abstract data type. More...

#include <buffer.h>

Inheritance diagram for tf2_ros::Buffer:
Inheritance graph
[legend]

Public Member Functions

 Buffer (ros::Duration cache_time=ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug=false)
 Constructor for a Buffer object. More...
 
virtual 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, const ros::Duration timeout, std::string *errstr=NULL) const
 Test if a transform is possible. More...
 
virtual bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &target_time, const ros::Duration timeout, std::string *errstr=NULL) const
 Test if a transform is possible. More...
 
virtual 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 ros::Duration timeout) const
 Get the transform between two frames by frame ID assuming fixed frame. More...
 
virtual geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
 Get the transform between two frames by frame ID. More...
 
- Public Member Functions inherited from tf2_ros::BufferInterface
template<class A , class B >
B & transform (const A &in, B &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
 Transform an input into the target frame and convert to a specified output type (advanced). It is templated on two types: the type of the input object and the type of the transformed output. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
template<class A , class B >
B & transform (const A &in, B &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
 Transform an input into the target frame and convert to a specified output type. It is templated on two types: the type of the input object and the type of the transformed output. For example, the template types could be Transform, Pose, Vector, or Quaternion messages type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. More...
 
template<class T >
transform (const T &in, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
 Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
template<class T >
transform (const T &in, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
 Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). More...
 
template<class T >
T & transform (const T &in, T &out, const std::string &target_frame, const ros::Time &target_time, const std::string &fixed_frame, ros::Duration timeout=ros::Duration(0.0)) const
 Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
template<class T >
T & transform (const T &in, T &out, const std::string &target_frame, ros::Duration timeout=ros::Duration(0.0)) const
 Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). More...
 
- Public Member Functions inherited from tf2::BufferCore
boost::signals2::connection _addTransformsChangedListener (boost::function< void(void)> callback)
 
std::string _allFramesAsDot () const
 
std::string _allFramesAsDot (double current_time) 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
 
bool _frameExists (const std::string &frame_id_str) const
 
void _getFrameStrings (std::vector< std::string > &ids) const
 
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
 
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)
 
TransformableRequestHandle addTransformableRequest (TransformableCallbackHandle handle, const std::string &target_frame, const std::string &source_frame, ros::Time time)
 
std::string allFramesAsString () const
 
std::string allFramesAsYAML () const
 
std::string allFramesAsYAML (double current_time) const
 
 BufferCore (ros::Duration cache_time_=ros::Duration(DEFAULT_CACHE_TIME))
 
void cancelTransformableRequest (TransformableRequestHandle handle)
 
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
 
bool canTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
 
void clear ()
 
ros::Duration getCacheLength ()
 
bool isUsingDedicatedThread () const
 
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
 
geometry_msgs::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const ros::Time &time) const
 
void removeTransformableCallback (TransformableCallbackHandle handle)
 
bool setTransform (const geometry_msgs::TransformStamped &transform, const std::string &authority, bool is_static=false)
 
void setUsingDedicatedThread (bool value)
 
virtual ~BufferCore (void)
 

Private Member Functions

bool checkAndErrorDedicatedThreadPresent (std::string *errstr) const
 
bool getFrames (tf2_msgs::FrameGraph::Request &req, tf2_msgs::FrameGraph::Response &res)
 

Private Attributes

ros::ServiceServer frames_server_
 

Additional Inherited Members

- Public Types inherited from tf2::BufferCore
typedef boost::function< void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time time, TransformableResult result)> TransformableCallback
 
- Static Public Attributes inherited from tf2::BufferCore
static const int DEFAULT_CACHE_TIME
 
static const uint32_t MAX_GRAPH_DEPTH
 

Detailed Description

Standard implementation of the tf2_ros::BufferInterface abstract data type.

Inherits tf2_ros::BufferInterface and tf2::BufferCore. Stores known frames and optionally offers a ROS service, "tf2_frames", which responds to client requests with a response containing a tf2_msgs::FrameGraph representing the relationship of known frames.

Definition at line 51 of file buffer.h.

Constructor & Destructor Documentation

◆ Buffer()

tf2_ros::Buffer::Buffer ( ros::Duration  cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME),
bool  debug = false 
)

Constructor for a Buffer object.

Parameters
cache_timeHow long to keep a history of transforms
debugWhether to advertise the tf2_frames service that exposes debugging information from the buffer
Returns

Definition at line 43 of file buffer.cpp.

Member Function Documentation

◆ canTransform() [1/2]

bool tf2_ros::Buffer::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,
const ros::Duration  timeout,
std::string *  errstr = NULL 
) const
virtual

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
timeoutHow long to block before failing
errstrA 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

Implements tf2_ros::BufferInterface.

Definition at line 148 of file buffer.cpp.

◆ canTransform() [2/2]

bool tf2_ros::Buffer::canTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time target_time,
const ros::Duration  timeout,
std::string *  errstr = NULL 
) const
virtual

Test if a transform is possible.

Parameters
target_frameThe frame into which to transform
source_frameThe frame from which to transform
target_timeThe time at which to transform
timeoutHow long to block before failing
errstrA 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

Implements tf2_ros::BufferInterface.

Definition at line 119 of file buffer.cpp.

◆ checkAndErrorDedicatedThreadPresent()

bool tf2_ros::Buffer::checkAndErrorDedicatedThreadPresent ( std::string *  errstr) const
private

Definition at line 185 of file buffer.cpp.

◆ getFrames()

bool tf2_ros::Buffer::getFrames ( tf2_msgs::FrameGraph::Request &  req,
tf2_msgs::FrameGraph::Response &  res 
)
private

Definition at line 177 of file buffer.cpp.

◆ lookupTransform() [1/2]

geometry_msgs::TransformStamped tf2_ros::Buffer::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 ros::Duration  timeout 
) const
virtual

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.
timeoutHow long to block before failing
Returns
The transform between the frames

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

Implements tf2_ros::BufferInterface.

Definition at line 63 of file buffer.cpp.

◆ lookupTransform() [2/2]

geometry_msgs::TransformStamped tf2_ros::Buffer::lookupTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
const ros::Duration  timeout 
) const
virtual

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)
timeoutHow long to block before failing
Returns
The transform between the frames

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

Implements tf2_ros::BufferInterface.

Definition at line 54 of file buffer.cpp.

Member Data Documentation

◆ frames_server_

ros::ServiceServer tf2_ros::Buffer::frames_server_
private

Definition at line 134 of file buffer.h.


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


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Sun Feb 4 2024 03:18:16