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_
39 #include <tf2/buffer_core.h>
42 #include <geometry_msgs/msg/transform_stamped.hpp>
43 #include <tf2_msgs/srv/frame_graph.hpp>
44 #include <rclcpp/rclcpp.hpp>
50 #include <unordered_map>
64 using tf2::BufferCore::lookupTransform;
65 using tf2::BufferCore::canTransform;
73 rclcpp::Clock::SharedPtr clock,
74 tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME),
75 rclcpp::Node::SharedPtr node = rclcpp::Node::SharedPtr());
88 geometry_msgs::msg::TransformStamped
91 const tf2::TimePoint & time,
const tf2::Duration timeout)
const override;
98 geometry_msgs::msg::TransformStamped
101 const rclcpp::Time & time,
102 const rclcpp::Duration timeout = rclcpp::Duration::from_nanoseconds(0))
const
120 geometry_msgs::msg::TransformStamped
122 const std::string & target_frame,
const tf2::TimePoint & target_time,
123 const std::string & source_frame,
const tf2::TimePoint & source_time,
124 const std::string & fixed_frame,
const tf2::Duration timeout)
const override;
132 geometry_msgs::msg::TransformStamped
134 const std::string & target_frame,
const rclcpp::Time & target_time,
135 const std::string & source_frame,
const rclcpp::Time & source_time,
137 const rclcpp::Duration timeout = rclcpp::Duration::from_nanoseconds(0))
const
157 const tf2::TimePoint & target_time,
const tf2::Duration timeout,
168 const rclcpp::Time & time,
169 const rclcpp::Duration timeout = rclcpp::Duration::from_nanoseconds(0),
188 const std::string & target_frame,
const tf2::TimePoint & target_time,
189 const std::string & source_frame,
const tf2::TimePoint & source_time,
190 const std::string & fixed_frame,
const tf2::Duration timeout,
202 const std::string & target_frame,
const rclcpp::Time & target_time,
203 const std::string & source_frame,
const rclcpp::Time & source_time,
205 const rclcpp::Duration timeout = rclcpp::Duration::from_nanoseconds(0),
235 const tf2::TimePoint & time,
const tf2::Duration & timeout,
246 const rclcpp::Time & time,
250 target_frame, source_frame,
259 timer_interface_ = create_timer_interface;
270 const tf2_msgs::srv::FrameGraph::Request::SharedPtr req,
271 tf2_msgs::srv::FrameGraph::Response::SharedPtr res);
273 void onTimeJump(
const rcl_time_jump_t & jump);
276 bool checkAndErrorDedicatedThreadPresent(
std::string * errstr)
const;
279 rclcpp::Logger getLogger()
const;
282 rclcpp::Service<tf2_msgs::srv::FrameGraph>::SharedPtr frames_server_;
285 rclcpp::Clock::SharedPtr clock_;
288 rclcpp::Node::SharedPtr node_;
300 rclcpp::JumpHandler::SharedPtr jump_handler_;
303 static const char threading_error[] =
"Do not call canTransform or lookupTransform with a timeout "
304 "unless you are using another thread for populating data. Without a dedicated thread it will "
305 "always timeout. If you have a separate thread servicing tf messages, call "
306 "setUsingDedicatedThread(true) on your Buffer instance.";
310 #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:48
Abstract interface for wrapping tf2::BufferCoreInterface in a ROS-based API. Implementations include ...
Definition: buffer_interface.h:127
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::from_nanoseconds(0), std::string *errstr=NULL) const
Test if a transform is possible.
Definition: buffer.h:201
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::from_nanoseconds(0)) const
Get the transform between two frames by frame ID.
Definition: buffer.h:99
Abstract interface for asynchronous operations on a tf2::BufferCoreInterface. Implementations include...
Definition: async_buffer_interface.h:53
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:100
TF2_ROS_PUBLIC Buffer(rclcpp::Clock::SharedPtr clock, tf2::Duration cache_time=tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME), rclcpp::Node::SharedPtr node=rclcpp::Node::SharedPtr())
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::from_nanoseconds(0), std::string *errstr=NULL) const
Test if a transform is possible.
Definition: buffer.h:166
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:43
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::from_nanoseconds(0)) const
Get the transform between two frames by frame ID assuming fixed frame.
Definition: buffer.h:133
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:244
TF2_ROS_PUBLIC void setCreateTimerInterface(CreateTimerInterface::SharedPtr create_timer_interface)
Definition: buffer.h:257
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer.h:61
#define TF2_ROS_PUBLIC
Definition: visibility_control.h:58