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

Action client-based implementation of the tf2_ros::BufferInterface abstract data type. More...

#include <buffer_client.h>

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

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. More...
 
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. 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=ros::Duration(0.0), std::string *errstr=NULL) const
 Test if a transform is possible. More...
 
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. 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=ros::Duration(0.0)) const
 Get the transform between two frames by frame ID assuming fixed frame. More...
 
bool waitForServer (const ros::Duration &timeout=ros::Duration(0))
 Block until the action server is ready to respond to requests. More...
 
- Public Member Functions inherited from tf2_ros::BufferInterface
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...
 
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 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 >
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 >
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 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...
 

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

Action client-based implementation of the tf2_ros::BufferInterface abstract data type.

BufferClient uses actionlib to coordinate waiting for available transforms.

You can use this class with a tf2_ros::BufferServer and tf2_ros::TransformListener in a separate process.

Definition at line 52 of file buffer_client.h.

Member Typedef Documentation

Definition at line 55 of file buffer_client.h.

Constructor & Destructor Documentation

tf2_ros::BufferClient::BufferClient ( std::string  ns,
double  check_frequency = 10.0,
ros::Duration  timeout_padding = ros::Duration(2.0) 
)

BufferClient constructor.

Parameters
nsThe namespace in which to look for a BufferServer
check_frequencyThe frequency in Hz to check whether the BufferServer has completed a request
timeout_paddingThe 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_ros::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_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 132 of file buffer_client.cpp.

bool tf2_ros::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_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 151 of file buffer_client.cpp.

geometry_msgs::TransformStamped tf2_ros::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_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 48 of file buffer_client.cpp.

geometry_msgs::TransformStamped tf2_ros::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_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 62 of file buffer_client.cpp.

geometry_msgs::TransformStamped tf2_ros::BufferClient::processGoal ( const tf2_msgs::LookupTransformGoal &  goal) const
private

Definition at line 79 of file buffer_client.cpp.

geometry_msgs::TransformStamped tf2_ros::BufferClient::processResult ( const tf2_msgs::LookupTransformResult &  result) const
private

Definition at line 106 of file buffer_client.cpp.

bool tf2_ros::BufferClient::waitForServer ( const ros::Duration timeout = ros::Duration(0))
inline

Block until the action server is ready to respond to requests.

Parameters
timeoutTime to wait for the server.
Returns
True if the server is ready, false otherwise.

Definition at line 126 of file buffer_client.h.

Member Data Documentation

double tf2_ros::BufferClient::check_frequency_
private

Definition at line 135 of file buffer_client.h.

LookupActionClient tf2_ros::BufferClient::client_
mutableprivate

Definition at line 134 of file buffer_client.h.

ros::Duration tf2_ros::BufferClient::timeout_padding_
private

Definition at line 136 of file buffer_client.h.


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


tf2_ros
Author(s): Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Fri Oct 16 2020 19:08:54