|
TF2_ROS_PUBLIC | Buffer (rclcpp::Clock::SharedPtr clock, tf2::Duration cache_time=tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME)) |
| Constructor for a Buffer object. More...
|
|
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 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 std::string &source_frame, const rclcpp::Time &time, const rclcpp::Duration timeout=rclcpp::Duration(0)) const |
| 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) const override |
| Get the transform between two frames by frame ID assuming fixed frame. More...
|
|
TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped | lookupTransform (const std::string &target_frame, const rclcpp::Time &target_time, const std::string &source_frame, const rclcpp::Time &source_time, const std::string &fixed_frame, const rclcpp::Duration timeout=rclcpp::Duration(0)) const |
| 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 &target_time, const tf2::Duration timeout, std::string *errstr=NULL) const override |
| Test if a transform is possible. More...
|
|
TF2_ROS_PUBLIC bool | canTransform (const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const rclcpp::Duration timeout=rclcpp::Duration(0), std::string *errstr=NULL) const |
| 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, std::string *errstr=NULL) const override |
| Test if a transform is possible. More...
|
|
TF2_ROS_PUBLIC bool | canTransform (const std::string &target_frame, const rclcpp::Time &target_time, const std::string &source_frame, const rclcpp::Time &source_time, const std::string &fixed_frame, const rclcpp::Duration timeout=rclcpp::Duration(0), std::string *errstr=NULL) const |
| Test if a transform is possible. More...
|
|
TF2_ROS_PUBLIC TransformStampedFuture | waitForTransform (const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration &timeout, TransformReadyCallback callback) override |
| Wait for a transform between two frames to become available. More...
|
|
TF2_ROS_PUBLIC TransformStampedFuture | waitForTransform (const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const rclcpp::Duration &timeout, TransformReadyCallback callback) |
| Wait for a transform between two frames to become available. More...
|
|
TF2_ROS_PUBLIC void | setCreateTimerInterface (CreateTimerInterface::SharedPtr create_timer_interface) |
|
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 () |
|
virtual TF2_ROS_PUBLIC | ~AsyncBufferInterface ()=default |
|
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Inherits tf2_ros::BufferInterface and tf2::BufferCore. Stores known frames and offers a ROS service, "tf_frames", which responds to client requests with a response containing a tf2_msgs::FrameGraph representing the relationship of known frames.