tf2_ros
master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
|
Go to the documentation of this file.
32 #ifndef TF2_ROS_BUFFER_H
33 #define TF2_ROS_BUFFER_H
37 #include <unordered_map>
43 #include <tf2/buffer_core.h>
44 #include <tf2_msgs/srv/frame_graph.hpp>
45 #include <rclcpp/rclcpp.hpp>
61 using tf2::BufferCore::lookupTransform;
62 using tf2::BufferCore::canTransform;
71 TF2_ROS_PUBLIC Buffer(rclcpp::Clock::SharedPtr clock, tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME));
84 geometry_msgs::msg::TransformStamped
86 const tf2::TimePoint& time,
const tf2::Duration timeout)
const override;
93 geometry_msgs::msg::TransformStamped
95 const rclcpp::Time & time,
const rclcpp::Duration timeout=rclcpp::Duration(0))
const
113 geometry_msgs::msg::TransformStamped
115 const std::string& source_frame,
const tf2::TimePoint& source_time,
116 const std::string& fixed_frame,
const tf2::Duration timeout)
const override;
124 geometry_msgs::msg::TransformStamped
126 const std::string & source_frame,
const rclcpp::Time & source_time,
127 const std::string & fixed_frame,
const rclcpp::Duration timeout=rclcpp::Duration(0))
const
146 const tf2::TimePoint& target_time,
const tf2::Duration timeout,
std::string* errstr = NULL)
const override;
155 const rclcpp::Time & time,
const rclcpp::Duration timeout=rclcpp::Duration(0),
174 const std::string& source_frame,
const tf2::TimePoint& source_time,
186 const std::string & source_frame,
const rclcpp::Time & source_time,
187 const std::string & fixed_frame,
const rclcpp::Duration timeout=rclcpp::Duration(0),
225 const rclcpp::Time & time,
229 target_frame, source_frame,
238 timer_interface_ = create_timer_interface;
242 void timerCallback(
const TimerHandle & timer_handle,
247 bool getFrames(tf2_msgs::srv::FrameGraph::Request& req, tf2_msgs::srv::FrameGraph::Response& res) ;
249 void onTimeJump(
const rcl_time_jump_t & jump);
252 bool checkAndErrorDedicatedThreadPresent(
std::string* errstr)
const;
258 rclcpp::Clock::SharedPtr clock_;
270 rclcpp::JumpHandler::SharedPtr jump_handler_;
273 static const std::string threading_error =
"Do not call canTransform or lookupTransform with a timeout unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a seperate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance.";
278 #endif // TF2_ROS_BUFFER_H
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.
uint64_t TimerHandle
Definition: create_timer_interface.h:44
Abstract interface for wrapping tf2::BufferCoreInterface in a ROS-based API. Implementations include ...
Definition: buffer_interface.h:120
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.
Definition: buffer.h:94
Abstract interface for asynchronous operations on a tf2::BufferCoreInterface. Implementations include...
Definition: async_buffer_interface.h:51
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.
tf2::TimePoint fromRclcpp(const rclcpp::Time &time)
Definition: buffer_interface.h:93
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.
Definition: async_buffer_interface.h:41
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.
Definition: buffer.h:224
TF2_ROS_PUBLIC void setCreateTimerInterface(CreateTimerInterface::SharedPtr create_timer_interface)
Definition: buffer.h:236
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer.h:58
#define TF2_ROS_PUBLIC
Definition: visibility_control.h:58
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.
Definition: buffer.h:125
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.
Definition: buffer.h:185
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.
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.
Definition: buffer.h:154