$search

tf2::BufferClient Class Reference

#include <buffer_client.h>

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

List of all members.

Public Types

typedef
actionlib::SimpleActionClient
< tf2_msgs::LookupTransformAction
LookupActionClient

Public Member Functions

 BufferClient (std::string ns, double check_frequency=10.0, ros::Duration timeout_padding_=ros::Duration(2.0))
 BufferClient constructor.
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=ros::Duration(0.0), 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 &time, const ros::Duration timeout=ros::Duration(0.0), 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=ros::Duration(0.0)) 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=ros::Duration(0.0)) const
 Get the transform between two frames by frame ID.
bool waitForServer (const ros::Duration &timeout=ros::Duration(0))

Private Member Functions

geometry_msgs::TransformStamped processGoal (const tf2_msgs::LookupTransformGoal &goal) const
geometry_msgs::TransformStamped processResult (const tf2_msgs::LookupTransformResult &result) const

Private Attributes

double check_frequency_
LookupActionClient client_
ros::Duration timeout_padding_

Detailed Description

Definition at line 46 of file buffer_client.h.


Member Typedef Documentation

Definition at line 49 of file buffer_client.h.


Constructor & Destructor Documentation

tf2::BufferClient::BufferClient ( std::string  ns,
double  check_frequency = 10.0,
ros::Duration  timeout_padding_ = ros::Duration(2.0) 
)

BufferClient constructor.

Parameters:
ns The namespace in which to look for a BufferServer
check_frequency The frequency in Hz to check whether the BufferServer has completed a request
timeout_paddind The amount of time to allow passed the desired timeout on the client side for communication lag

Definition at line 41 of file buffer_client.cpp.


Member Function Documentation

bool tf2::BufferClient::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 = ros::Duration(0.0),
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 148 of file buffer_client.cpp.

bool tf2::BufferClient::canTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
const ros::Duration  timeout = ros::Duration(0.0),
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 132 of file buffer_client.cpp.

geometry_msgs::TransformStamped tf2::BufferClient::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 = ros::Duration(0.0) 
) 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 62 of file buffer_client.cpp.

geometry_msgs::TransformStamped tf2::BufferClient::lookupTransform ( const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time,
const ros::Duration  timeout = ros::Duration(0.0) 
) 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_client.cpp.

geometry_msgs::TransformStamped tf2::BufferClient::processGoal ( const tf2_msgs::LookupTransformGoal goal  )  const [private]

Definition at line 79 of file buffer_client.cpp.

geometry_msgs::TransformStamped tf2::BufferClient::processResult ( const tf2_msgs::LookupTransformResult result  )  const [private]

Definition at line 106 of file buffer_client.cpp.

bool tf2::BufferClient::waitForServer ( const ros::Duration timeout = ros::Duration(0)  )  [inline]

Definition at line 116 of file buffer_client.h.


Member Data Documentation

Definition at line 125 of file buffer_client.h.

Definition at line 124 of file buffer_client.h.

Definition at line 126 of file buffer_client.h.


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


tf2_ros
Author(s): Wim Meeussen, Eitan Marder-Eppstein
autogenerated on Tue Mar 5 11:59:03 2013