tf2_ros  master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
Public Types | Public Member Functions | 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]
Collaboration diagram for tf2_ros::BufferClient:
Collaboration graph
[legend]

Public Types

using LookupTransformAction = tf2_msgs::action::LookupTransform
 

Public Member Functions

template<typename NodePtr >
 BufferClient (NodePtr node, const std::string ns, const double &check_frequency=10.0, const tf2::Duration &timeout_padding=tf2::durationFromSec(2.0))
 BufferClient constructor. More...
 
virtual ~BufferClient ()=default
 
TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration timeout=tf2::durationFromSec(0.0)) const override
 Get the transform between two frames by frame ID. More...
 
TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform (const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &source_frame, const tf2::TimePoint &source_time, const std::string &fixed_frame, const tf2::Duration timeout=tf2::durationFromSec(0.0)) const override
 Get the transform between two frames by frame ID assuming fixed frame. More...
 
TF2_ROS_PUBLIC bool canTransform (const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration timeout=tf2::durationFromSec(0.0), std::string *errstr=nullptr) const override
 Test if a transform is possible. More...
 
TF2_ROS_PUBLIC bool canTransform (const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &source_frame, const tf2::TimePoint &source_time, const std::string &fixed_frame, const tf2::Duration timeout=tf2::durationFromSec(0.0), std::string *errstr=nullptr) const override
 Test if a transform is possible. More...
 
TF2_ROS_PUBLIC bool waitForServer (const tf2::Duration &timeout=tf2::durationFromSec(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, tf2::Duration timeout=tf2::durationFromSec(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, tf2::Duration timeout=tf2::durationFromSec(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, tf2::Duration timeout=tf2::durationFromSec(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 tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(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 tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(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 tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(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...
 
virtual ~BufferInterface ()
 

Detailed Description

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

BufferClient uses actions to coordinate waiting for available transforms.

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

Member Typedef Documentation

◆ LookupTransformAction

using tf2_ros::BufferClient::LookupTransformAction = tf2_msgs::action::LookupTransform

Constructor & Destructor Documentation

◆ BufferClient()

template<typename NodePtr >
tf2_ros::BufferClient::BufferClient ( NodePtr  node,
const std::string  ns,
const double &  check_frequency = 10.0,
const tf2::Duration &  timeout_padding = tf2::durationFromSec(2.0) 
)
inline

BufferClient constructor.

Parameters
nodeThe node to add the buffer client to
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

◆ ~BufferClient()

virtual tf2_ros::BufferClient::~BufferClient ( )
virtualdefault

Member Function Documentation

◆ lookupTransform() [1/2]

TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped tf2_ros::BufferClient::lookupTransform ( const std::string target_frame,
const std::string source_frame,
const tf2::TimePoint &  time,
const tf2::Duration  timeout = tf2::durationFromSec(0.0) 
) const
overridevirtual

Get the transform between two frames by frame ID.

If there is a communication failure, timeout, or transformation error, an exception is thrown.

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
Exceptions
tf2::TransformExceptionOne of the following
  • tf2::LookupException
  • tf2::ConnectivityException
  • tf2::ExtrapolationException
  • tf2::InvalidArgumentException
tf2_ros::LookupTransformGoalExceptionOne of the following

Implements tf2_ros::BufferInterface.

◆ lookupTransform() [2/2]

TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped tf2_ros::BufferClient::lookupTransform ( const std::string target_frame,
const tf2::TimePoint &  target_time,
const std::string source_frame,
const tf2::TimePoint &  source_time,
const std::string fixed_frame,
const tf2::Duration  timeout = tf2::durationFromSec(0.0) 
) const
overridevirtual

Get the transform between two frames by frame ID assuming fixed frame.

If there is a communication failure, timeout, or transformation error, an exception is thrown.

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
Exceptions
tf2::TransformExceptionOne of the following
  • tf2::LookupException
  • tf2::ConnectivityException
  • tf2::ExtrapolationException
  • tf2::InvalidArgumentException
tf2_ros::LookupTransformGoalExceptionOne of the following

Implements tf2_ros::BufferInterface.

◆ canTransform() [1/2]

TF2_ROS_PUBLIC bool tf2_ros::BufferClient::canTransform ( const std::string target_frame,
const std::string source_frame,
const tf2::TimePoint &  time,
const tf2::Duration  timeout = tf2::durationFromSec(0.0),
std::string errstr = nullptr 
) const
overridevirtual

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.

◆ canTransform() [2/2]

TF2_ROS_PUBLIC bool tf2_ros::BufferClient::canTransform ( const std::string target_frame,
const tf2::TimePoint &  target_time,
const std::string source_frame,
const tf2::TimePoint &  source_time,
const std::string fixed_frame,
const tf2::Duration  timeout = tf2::durationFromSec(0.0),
std::string errstr = nullptr 
) const
overridevirtual

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.

◆ waitForServer()

TF2_ROS_PUBLIC bool tf2_ros::BufferClient::waitForServer ( const tf2::Duration &  timeout = tf2::durationFromSec(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.

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