tf2_ros  master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
buffer.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
32 #ifndef TF2_ROS__BUFFER_H_
33 #define TF2_ROS__BUFFER_H_
34 
39 #include <tf2/buffer_core.h>
40 #include <tf2/time.h>
41 
42 #include <geometry_msgs/msg/transform_stamped.hpp>
43 #include <tf2_msgs/srv/frame_graph.hpp>
44 #include <rclcpp/rclcpp.hpp>
45 
46 #include <future>
47 #include <memory>
48 #include <mutex>
49 #include <string>
50 #include <unordered_map>
51 
52 namespace tf2_ros
53 {
54 
61 class Buffer : public BufferInterface, public AsyncBufferInterface, public tf2::BufferCore
62 {
63 public:
64  using tf2::BufferCore::lookupTransform;
65  using tf2::BufferCore::canTransform;
66 
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());
76 
88  geometry_msgs::msg::TransformStamped
90  const std::string & target_frame, const std::string & source_frame,
91  const tf2::TimePoint & time, const tf2::Duration timeout) const override;
92 
98  geometry_msgs::msg::TransformStamped
100  const std::string & target_frame, const std::string & source_frame,
101  const rclcpp::Time & time,
102  const rclcpp::Duration timeout = rclcpp::Duration::from_nanoseconds(0)) const
103  {
104  return lookupTransform(target_frame, source_frame, fromRclcpp(time), fromRclcpp(timeout));
105  }
106 
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;
125 
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,
136  const std::string & fixed_frame,
137  const rclcpp::Duration timeout = rclcpp::Duration::from_nanoseconds(0)) const
138  {
139  return lookupTransform(
140  target_frame, fromRclcpp(target_time),
141  source_frame, fromRclcpp(source_time),
142  fixed_frame, fromRclcpp(timeout));
143  }
144 
154  bool
155  canTransform(
156  const std::string & target_frame, const std::string & source_frame,
157  const tf2::TimePoint & target_time, const tf2::Duration timeout,
158  std::string * errstr = NULL) const override;
159 
165  bool
167  const std::string & target_frame, const std::string & source_frame,
168  const rclcpp::Time & time,
169  const rclcpp::Duration timeout = rclcpp::Duration::from_nanoseconds(0),
170  std::string * errstr = NULL) const
171  {
172  return canTransform(target_frame, source_frame, fromRclcpp(time), fromRclcpp(timeout), errstr);
173  }
174 
186  bool
187  canTransform(
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,
191  std::string * errstr = NULL) const override;
192 
200  bool
202  const std::string & target_frame, const rclcpp::Time & target_time,
203  const std::string & source_frame, const rclcpp::Time & source_time,
204  const std::string & fixed_frame,
205  const rclcpp::Duration timeout = rclcpp::Duration::from_nanoseconds(0),
206  std::string * errstr = NULL) const
207  {
208  return canTransform(
209  target_frame, fromRclcpp(target_time),
210  source_frame, fromRclcpp(source_time),
211  fixed_frame, fromRclcpp(timeout),
212  errstr);
213  }
214 
234  const std::string & target_frame, const std::string & source_frame,
235  const tf2::TimePoint & time, const tf2::Duration & timeout,
236  TransformReadyCallback callback) override;
237 
245  const std::string & target_frame, const std::string & source_frame,
246  const rclcpp::Time & time,
247  const rclcpp::Duration & timeout, TransformReadyCallback callback)
248  {
249  return waitForTransform(
250  target_frame, source_frame,
251  fromRclcpp(time), fromRclcpp(timeout),
252  callback);
253  }
254 
256  inline void
258  {
259  timer_interface_ = create_timer_interface;
260  }
261 
262 private:
263  void timerCallback(
264  const TimerHandle & timer_handle,
266  TransformStampedFuture future,
267  TransformReadyCallback callback);
268 
269  bool getFrames(
270  const tf2_msgs::srv::FrameGraph::Request::SharedPtr req,
271  tf2_msgs::srv::FrameGraph::Response::SharedPtr res);
272 
273  void onTimeJump(const rcl_time_jump_t & jump);
274 
275  // conditionally error if dedicated_thread unset.
276  bool checkAndErrorDedicatedThreadPresent(std::string * errstr) const;
277 
279  rclcpp::Logger getLogger() const;
280 
281  // framegraph service
282  rclcpp::Service<tf2_msgs::srv::FrameGraph>::SharedPtr frames_server_;
283 
285  rclcpp::Clock::SharedPtr clock_;
286 
288  rclcpp::Node::SharedPtr node_;
289 
291  CreateTimerInterface::SharedPtr timer_interface_;
292 
295 
297  std::mutex timer_to_request_map_mutex_;
298 
300  rclcpp::JumpHandler::SharedPtr jump_handler_;
301 };
302 
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.";
307 
308 } // namespace tf2_ros
309 
310 #endif // TF2_ROS__BUFFER_H_
tf2_ros::Buffer::waitForTransform
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.
std::shared_future
std::string
std::shared_ptr< CreateTimerInterface >
tf2_ros::TimerHandle
uint64_t TimerHandle
Definition: create_timer_interface.h:48
tf2_ros::BufferInterface
Abstract interface for wrapping tf2::BufferCoreInterface in a ROS-based API. Implementations include ...
Definition: buffer_interface.h:127
tf2_ros::Buffer::canTransform
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::Buffer::lookupTransform
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
std::promise
tf2_ros::AsyncBufferInterface
Abstract interface for asynchronous operations on a tf2::BufferCoreInterface. Implementations include...
Definition: async_buffer_interface.h:53
tf2_ros::Buffer::lookupTransform
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_ros::fromRclcpp
tf2::TimePoint fromRclcpp(const rclcpp::Time &time)
Definition: buffer_interface.h:100
std::function
tf2_ros::Buffer::Buffer
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::Buffer::canTransform
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
buffer_interface.h
tf2_ros::Buffer::canTransform
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.
tf2_ros
Definition: async_buffer_interface.h:43
tf2_ros::Buffer::lookupTransform
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::Buffer::waitForTransform
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
create_timer_interface.h
tf2_ros::Buffer::setCreateTimerInterface
TF2_ROS_PUBLIC void setCreateTimerInterface(CreateTimerInterface::SharedPtr create_timer_interface)
Definition: buffer.h:257
tf2_ros::Buffer
Standard implementation of the tf2_ros::BufferInterface abstract data type.
Definition: buffer.h:61
TF2_ROS_PUBLIC
#define TF2_ROS_PUBLIC
Definition: visibility_control.h:58
visibility_control.h
async_buffer_interface.h
std::mutex
std::unordered_map< TimerHandle, tf2::TransformableRequestHandle >