tf2_ros
master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
|
Abstract interface for wrapping tf2::BufferCoreInterface in a ROS-based API. Implementations include tf2_ros::Buffer and tf2_ros::BufferClient. More...
#include <buffer_interface.h>
Public Member Functions | |
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) const =0 |
Get the transform between two frames by frame ID. More... | |
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) const =0 |
Get the transform between two frames by frame ID assuming fixed frame. More... | |
virtual TF2_ROS_PUBLIC bool | canTransform (const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration timeout, std::string *errstr=NULL) const =0 |
Test if a transform is possible. More... | |
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, std::string *errstr=NULL) const =0 |
Test if a transform is possible. More... | |
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 > | |
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 > | |
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 () |
Abstract interface for wrapping tf2::BufferCoreInterface in a ROS-based API. Implementations include tf2_ros::Buffer and tf2_ros::BufferClient.
|
inlinevirtual |
|
pure virtual |
Get the transform between two frames by frame ID.
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 |
Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException
Implemented in tf2_ros::BufferClient, and tf2_ros::Buffer.
|
pure virtual |
Get the transform between two frames by frame ID assuming fixed frame.
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 |
Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException
Implemented in tf2_ros::BufferClient, and tf2_ros::Buffer.
|
pure virtual |
Test if a transform is possible.
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 |
Implemented in tf2_ros::BufferClient, and tf2_ros::Buffer.
|
pure virtual |
Test if a transform is possible.
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 |
Implemented in tf2_ros::BufferClient, and tf2_ros::Buffer.
|
inline |
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).
T | The type of the object to transform. |
in | The object to transform |
out | The transformed output, preallocated by the caller. |
target_frame | The string identifer for the frame to transform into. |
timeout | How long to wait for the target frame. Default value is zero (no blocking). |
|
inline |
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).
T | The type of the object to transform. |
in | The object to transform. |
target_frame | The string identifer for the frame to transform into. |
timeout | How long to wait for the target frame. Default value is zero (no blocking). |
|
inline |
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.
A | The type of the object to transform. |
B | The type of the transformed output. |
in | The object to transform |
out | The transformed output, converted to the specified type. |
target_frame | The string identifer for the frame to transform into. |
timeout | How long to wait for the target frame. Default value is zero (no blocking). |
|
inline |
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.
T | The type of the object to transform. |
in | The object to transform |
out | The transformed output, preallocated by the caller. |
target_frame | The string identifer for the frame to transform into. |
target_time | The time into which to transform |
fixed_frame | The frame in which to treat the transform as constant in time. |
timeout | How long to wait for the target frame. Default value is zero (no blocking). |
|
inline |
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.
T | The type of the object to transform. |
in | The object to transform |
target_frame | The string identifer for the frame to transform into. |
target_time | The time into which to transform |
fixed_frame | The frame in which to treat the transform as constant in time. |
timeout | How long to wait for the target frame. Default value is zero (no blocking). |
|
inline |
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.
A | The type of the object to transform. |
B | The type of the transformed output. |
in | The object to transform |
out | The transformed output, converted to the specified output type. |
target_frame | The string identifer for the frame to transform into. |
target_time | The time into which to transform |
fixed_frame | The frame in which to treat the transform as constant in time. |
timeout | How long to wait for the target frame. Default value is zero (no blocking). |