Public Member Functions | Private Member Functions | Private Attributes
tf2_ros::Buffer Class Reference

#include <buffer.h>

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

List of all members.

Public Member Functions

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

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_

Detailed Description

Definition at line 46 of file buffer.h.


Constructor & Destructor Documentation

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 view_frames service that exposes debugging information from the buffer
Returns:

Definition at line 40 of file buffer.cpp.


Member Function Documentation

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
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 104 of file buffer.cpp.

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 121 of file buffer.cpp.

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

Definition at line 146 of file buffer.cpp.

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

Definition at line 138 of file buffer.cpp.

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 51 of file buffer.cpp.

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 60 of file buffer.cpp.


Member Data Documentation

Definition at line 129 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 Thu Aug 27 2015 13:10:05