Class BufferClient
Defined in File buffer_client.h
Inheritance Relationships
Base Type
public tf2_ros::BufferInterface
(Class BufferInterface)
Class Documentation
-
class BufferClient : public tf2_ros::BufferInterface
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.
Public Types
-
using LookupTransformAction = tf2_msgs::action::LookupTransform
Public Functions
-
template<typename NodePtr>
inline BufferClient(NodePtr node, const std::string ns, const double &check_frequency = 10.0, const tf2::Duration &timeout_padding = tf2::durationFromSec(2.0)) BufferClient constructor.
- Parameters:
node – The node to add the buffer client to
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_padding – The amount of time to allow passed the desired timeout on the client side for communication lag
-
virtual ~BufferClient() = default
- virtual 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.
If there is a communication failure, timeout, or transformation error, an exception is thrown.
- 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
- Throws:
tf2::TransformException – One of the following
tf2::LookupException
tf2::ConnectivityException
tf2::ExtrapolationException
tf2::InvalidArgumentException
tf2_ros::LookupTransformGoalException – One of the following
- Returns:
The transform between the frames
- virtual 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.
If there is a communication failure, timeout, or transformation error, an exception is thrown.
- 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
- Throws:
tf2::TransformException – One of the following
tf2::LookupException
tf2::ConnectivityException
tf2::ExtrapolationException
tf2::InvalidArgumentException
tf2_ros::LookupTransformGoalException – One of the following
- Returns:
The transform between the frames
- virtual 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.
- 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
- virtual 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.
- 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
- inline TF2_ROS_PUBLIC bool waitForServer (const tf2::Duration &timeout=tf2::durationFromSec(0))
Block until the action server is ready to respond to requests.
- Parameters:
timeout – Time to wait for the server.
- Returns:
True if the server is ready, false otherwise.
-
using LookupTransformAction = tf2_msgs::action::LookupTransform