tf2::Buffer Class Reference

#include <buffer.h>

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

List of all members.

Public Member Functions

 Buffer (ros::Duration cache_time=ros::Duration(BufferCore::DEFAULT_CACHE_TIME), bool debug=true)
 Constructor for a Buffer object.
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.
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.
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.
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.

Private Member Functions

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

Private Attributes

ros::ServiceServer frames_server_

Detailed Description

Definition at line 42 of file buffer.h.


Constructor & Destructor Documentation

tf2::Buffer::Buffer ( ros::Duration  cache_time = ros::Duration(BufferCore::DEFAULT_CACHE_TIME),
bool  debug = true 
)

Constructor for a Buffer object.

Parameters:
cache_time How long to keep a history of transforms
debug Whether to advertise the view_frames service that exposes debugging information from the buffer
Returns:

Definition at line 38 of file buffer.cpp.


Member Function Documentation

bool tf2::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_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
timeout How long to block before failing
errstr 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

Implements tf2::BufferInterface.

Definition at line 80 of file buffer.cpp.

bool tf2::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_frame The frame into which to transform
source_frame The frame from which to transform
time The time at which to transform
timeout How long to block before failing
errstr 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

Implements tf2::BufferInterface.

Definition at line 67 of file buffer.cpp.

bool tf2::Buffer::getFrames ( tf2_msgs::FrameGraph::Request &  req,
tf2_msgs::FrameGraph::Response &  res 
) [inline, private]

Definition at line 112 of file buffer.h.

geometry_msgs::TransformStamped tf2::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_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.
timeout How long to block before failing
Returns:
The transform between the frames

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

Implements tf2::BufferInterface.

Definition at line 57 of file buffer.cpp.

geometry_msgs::TransformStamped tf2::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_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)
timeout How long to block before failing
Returns:
The transform between the frames

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

Implements tf2::BufferInterface.

Definition at line 48 of file buffer.cpp.


Member Data Documentation

ros::ServiceServer tf2::Buffer::frames_server_ [private]

Definition at line 118 of file buffer.h.


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


tf2_ros
Author(s): Wim Meeussen, Eitan Marder-Eppstein
autogenerated on Fri Jan 11 09:59:07 2013