tf2  master
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
buffer_core.h
Go to the documentation of this file.
1 // Copyright 2008, Willow Garage, Inc. All rights reserved.
2 //
3 // Redistribution and use in source and binary forms, with or without
4 // modification, are permitted provided that the following conditions are met:
5 //
6 // * Redistributions of source code must retain the above copyright
7 // notice, this list of conditions and the following disclaimer.
8 //
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 //
13 // * Neither the name of the {copyright_holder} 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 HOLDER 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__BUFFER_CORE_H_
33 #define TF2__BUFFER_CORE_H_
34 
35 #include <algorithm>
36 #include <cmath>
37 #include <functional>
38 #include <map>
39 #include <memory>
40 #include <mutex>
41 #include <string>
42 #include <unordered_map>
43 #include <utility>
44 #include <vector>
45 
46 #include "LinearMath/Transform.h"
47 #include "geometry_msgs/msg/transform_stamped.hpp"
49 #include "tf2/exceptions.h"
50 #include "tf2/transform_storage.h"
51 #include "tf2/visibility_control.h"
52 
53 namespace tf2
54 {
55 
57 typedef uint64_t TransformableRequestHandle;
58 
59 class TimeCacheInterface;
61 
63 {
66 };
67 
69 static constexpr Duration BUFFER_CORE_DEFAULT_CACHE_TIME = std::chrono::seconds(10);
70 
90 {
91 public:
92  /************* Constants ***********************/
95  static const uint32_t MAX_GRAPH_DEPTH = 1000UL;
96 
102  TF2_PUBLIC
103  explicit BufferCore(tf2::Duration cache_time_ = BUFFER_CORE_DEFAULT_CACHE_TIME);
104 
105  TF2_PUBLIC
106  virtual ~BufferCore(void);
107 
109  TF2_PUBLIC
110  void clear() override;
111 
118  TF2_PUBLIC
119  bool setTransform(
120  const geometry_msgs::msg::TransformStamped & transform,
121  const std::string & authority, bool is_static = false);
122 
123  /*********** Accessors *************/
124 
134  TF2_PUBLIC
135  geometry_msgs::msg::TransformStamped
137  const std::string & target_frame, const std::string & source_frame,
138  const TimePoint & time) const override;
139 
152  TF2_PUBLIC
153  geometry_msgs::msg::TransformStamped
155  const std::string & target_frame, const TimePoint & target_time,
156  const std::string & source_frame, const TimePoint & source_time,
157  const std::string & fixed_frame) const override;
158 
166  TF2_PUBLIC
167  bool canTransform(
168  const std::string & target_frame, const std::string & source_frame,
169  const TimePoint & time, std::string * error_msg = NULL) const override;
170 
180  TF2_PUBLIC
181  bool canTransform(
182  const std::string & target_frame, const TimePoint & target_time,
183  const std::string & source_frame, const TimePoint & source_time,
184  const std::string & fixed_frame, std::string * error_msg = NULL) const override;
185 
188  TF2_PUBLIC
190 
194  TF2_PUBLIC
195  std::string allFramesAsYAML(TimePoint current_time) const;
196 
199  TF2_PUBLIC
201 
205  TF2_PUBLIC
207 
209  void (TransformableRequestHandle request_handle, const std::string & target_frame,
210  const std::string & source_frame,
212 
214  TF2_PUBLIC
216  const TransformableCallback & cb,
217  const std::string & target_frame,
218  const std::string & source_frame,
219  TimePoint time);
221  TF2_PUBLIC
223 
224 
225  // Tell the buffer that there are multiple threads serviciing it.
226  // This is useful for derived classes to know if they can block or not.
227  TF2_PUBLIC
228  void setUsingDedicatedThread(bool value) {using_dedicated_thread_ = value;}
229  // Get the state of using_dedicated_thread_
230  TF2_PUBLIC
231  bool isUsingDedicatedThread() const {return using_dedicated_thread_;}
232 
233 
234  /* Backwards compatability section for tf::Transformer you should not use these
235  */
236 
239  TF2_PUBLIC
240  bool _frameExists(const std::string & frame_id_str) const;
241 
246  TF2_PUBLIC
247  bool _getParent(const std::string & frame_id, TimePoint time, std::string & parent) const;
248 
250  TF2_PUBLIC
251  void _getFrameStrings(std::vector<std::string> & ids) const;
252 
253 
254  TF2_PUBLIC
255  CompactFrameID _lookupFrameNumber(const std::string & frameid_str) const
256  {
257  return lookupFrameNumber(frameid_str);
258  }
259  TF2_PUBLIC
261  {
262  return lookupOrInsertFrameNumber(frameid_str);
263  }
264 
265  TF2_PUBLIC
267  CompactFrameID target_frame, CompactFrameID source_frame,
268  TimePoint & time, std::string * error_string) const
269  {
270  std::unique_lock<std::mutex> lock(frame_mutex_);
271  return getLatestCommonTime(target_frame, source_frame, time, error_string);
272  }
273 
274  TF2_PUBLIC
276  const char * function_name_arg,
277  const std::string & frame_id) const
278  {
279  return validateFrameId(function_name_arg, frame_id);
280  }
281 
283  TF2_PUBLIC
284  tf2::Duration getCacheLength() {return cache_time_;}
285 
289  TF2_PUBLIC
290  std::string _allFramesAsDot(TimePoint current_time) const;
291  TF2_PUBLIC
293 
297  TF2_PUBLIC
298  void _chainAsVector(
299  const std::string & target_frame, TimePoint target_time,
300  const std::string & source_frame, TimePoint source_time,
301  const std::string & fixed_frame,
302  std::vector<std::string> & output) const;
303 
304 private:
308  std::string allFramesAsStringNoLock() const;
309 
310 
311  /******************** Internal Storage ****************/
312 
315  typedef std::vector<TimeCacheInterfacePtr> V_TimeCacheInterface;
316  V_TimeCacheInterface frames_;
317 
319  mutable std::mutex frame_mutex_;
320 
322  typedef std::unordered_map<std::string, CompactFrameID> M_StringToCompactFrameID;
323  M_StringToCompactFrameID frameIDs_;
325  std::vector<std::string> frameIDs_reverse_;
327  std::map<CompactFrameID, std::string> frame_authority_;
328 
329 
331  tf2::Duration cache_time_;
332 
333  typedef uint32_t TransformableCallbackHandle;
334 
335  typedef std::unordered_map<TransformableCallbackHandle,
336  TransformableCallback> M_TransformableCallback;
337  M_TransformableCallback transformable_callbacks_;
338  uint32_t transformable_callbacks_counter_;
339  std::mutex transformable_callbacks_mutex_;
340 
341  struct TransformableRequest
342  {
343  TimePoint time;
344  TransformableRequestHandle request_handle;
345  TransformableCallbackHandle cb_handle;
346  CompactFrameID target_id;
347  CompactFrameID source_id;
348  std::string target_string;
349  std::string source_string;
350  };
351  typedef std::vector<TransformableRequest> V_TransformableRequest;
352  V_TransformableRequest transformable_requests_;
353  std::mutex transformable_requests_mutex_;
354  uint64_t transformable_requests_counter_;
355 
356 
357  /************************* Internal Functions ****************************/
358 
359  bool setTransformImpl(
360  const tf2::Transform & transform_in, const std::string frame_id,
361  const std::string child_frame_id, const TimePoint stamp,
362  const std::string & authority, bool is_static);
363  void lookupTransformImpl(
364  const std::string & target_frame, const std::string & source_frame,
365  const TimePoint & time_in, tf2::Transform & transform, TimePoint & time_out) const;
366 
367  void lookupTransformImpl(
368  const std::string & target_frame, const TimePoint & target_time,
369  const std::string & source_frame, const TimePoint & source_time,
370  const std::string & fixed_frame, tf2::Transform & transform, TimePoint & time_out) const;
371 
378  TimeCacheInterfacePtr getFrame(CompactFrameID c_frame_id) const;
379 
380  TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static);
381 
391  CompactFrameID validateFrameId(
392  const char * function_name_arg,
393  const std::string & frame_id,
394  std::string * error_msg) const;
395 
405  CompactFrameID validateFrameId(
406  const char * function_name_arg,
407  const std::string & frame_id) const;
408 
410  CompactFrameID lookupFrameNumber(const std::string & frameid_str) const;
411 
413  CompactFrameID lookupOrInsertFrameNumber(const std::string & frameid_str);
414 
416  const std::string & lookupFrameString(CompactFrameID frame_id_num) const;
417 
418  void createConnectivityErrorString(
419  CompactFrameID source_frame, CompactFrameID target_frame,
420  std::string * out) const;
421 
424  tf2::TF2Error getLatestCommonTime(
425  CompactFrameID target_frame, CompactFrameID source_frame,
426  TimePoint & time, std::string * error_string) const;
427 
428  template<typename F>
429  tf2::TF2Error walkToTopParent(
430  F & f, TimePoint time, CompactFrameID target_id,
431  CompactFrameID source_id, std::string * error_string) const;
432 
435  template<typename F>
436  tf2::TF2Error walkToTopParent(
437  F & f, TimePoint time, CompactFrameID target_id,
438  CompactFrameID source_id, std::string * error_string,
439  std::vector<CompactFrameID> * frame_chain) const;
440 
441  void testTransformableRequests();
442  // Thread safe transform check, acquire lock and call canTransformNoLock.
443  bool canTransformInternal(
444  CompactFrameID target_id, CompactFrameID source_id,
445  const TimePoint & time, std::string * error_msg) const;
446  // Actual implementation to walk the transform tree and find out if a transform exists.
447  bool canTransformNoLock(
448  CompactFrameID target_id, CompactFrameID source_id,
449  const TimePoint & time, std::string * error_msg) const;
450 
451  // Whether it is safe to use canTransform with a timeout.
452  // (If another thread is not provided it will always timeout.)
453  bool using_dedicated_thread_;
454 };
455 } // namespace tf2
456 
457 #endif // TF2__BUFFER_CORE_H_
tf2::BufferCore::getCacheLength
tf2::Duration getCacheLength()
Get the duration over which this transformer will cache.
Definition: buffer_core.h:284
exceptions.h
std::string
std::shared_ptr
tf2::BufferCore::setUsingDedicatedThread
void setUsingDedicatedThread(bool value)
Definition: buffer_core.h:228
buffer_core_interface.h
tf2::TimeCacheInterfacePtr
std::shared_ptr< TimeCacheInterface > TimeCacheInterfacePtr
Definition: buffer_core.h:60
std::pair
tf2::BufferCore::_chainAsVector
void _chainAsVector(const std::string &target_frame, TimePoint target_time, const std::string &source_frame, TimePoint source_time, const std::string &fixed_frame, std::vector< std::string > &output) const
Backwards compatabilityA way to see what frames are in a chain Useful for debugging.
tf2::BufferCore::setTransform
bool setTransform(const geometry_msgs::msg::TransformStamped &transform, const std::string &authority, bool is_static=false)
Add transform information to the tf data structure.
tf2::Duration
std::chrono::nanoseconds Duration
Definition: time.h:40
std::vector< std::string >
tf2::BufferCore::_validateFrameId
CompactFrameID _validateFrameId(const char *function_name_arg, const std::string &frame_id) const
Definition: buffer_core.h:275
std::chrono::seconds
tf2::BufferCoreInterface
Interface for providing coordinate transforms between any two frames in a system.
Definition: buffer_core_interface.h:48
tf2::BufferCore::MAX_GRAPH_DEPTH
static const uint32_t MAX_GRAPH_DEPTH
< Maximum graph search depth (deeper graphs will be assumed to have loops)
Definition: buffer_core.h:95
tf2::P_TimeAndFrameID
std::pair< TimePoint, CompactFrameID > P_TimeAndFrameID
Definition: buffer_core.h:56
Transform.h
tf2::BufferCore::allFramesAsYAML
std::string allFramesAsYAML() const
std::function
tf2::BufferCore::canTransform
bool canTransform(const std::string &target_frame, const std::string &source_frame, const TimePoint &time, std::string *error_msg=NULL) const override
Test if a transform is possible.
tf2::BufferCore::getAllFrameNames
std::vector< std::string > getAllFrameNames() const override
Get all frames that exist in the system.
tf2::BufferCore::BufferCore
BufferCore(tf2::Duration cache_time_=BUFFER_CORE_DEFAULT_CACHE_TIME)
tf2::BufferCore::_lookupFrameNumber
CompactFrameID _lookupFrameNumber(const std::string &frameid_str) const
Definition: buffer_core.h:255
tf2::CompactFrameID
uint32_t CompactFrameID
Definition: transform_storage.h:40
tf2::TransformFailure
@ TransformFailure
Definition: buffer_core.h:65
tf2::BufferCore::allFramesAsString
std::string allFramesAsString() const
A way to see what frames have been cached Useful for debugging.
tf2::TimePoint
std::chrono::time_point< std::chrono::system_clock, Duration > TimePoint
Definition: time.h:41
tf2::BufferCore::_getFrameStrings
void _getFrameStrings(std::vector< std::string > &ids) const
A way to get a std::vector of available frame ids.
tf2::TransformableRequestHandle
uint64_t TransformableRequestHandle
Definition: buffer_core.h:57
std::unique_lock
tf2::BufferCore::isUsingDedicatedThread
bool isUsingDedicatedThread() const
Definition: buffer_core.h:231
tf2::Transform
The Transform class supports rigid transforms with only translation and rotation and no scaling/shear...
Definition: Transform.h:33
std::chrono::time_point< std::chrono::system_clock, Duration >
transform_storage.h
tf2::BufferCore::_allFramesAsDot
std::string _allFramesAsDot() const
tf2::TimeCacheInterface
Definition: time_cache.h:47
tf2::BufferCore::_frameExists
bool _frameExists(const std::string &frame_id_str) const
Check if a frame exists in the tree.
std::map< CompactFrameID, std::string >
tf2::BufferCore::cancelTransformableRequest
void cancelTransformableRequest(TransformableRequestHandle handle)
Internal use only.
tf2::BufferCore::lookupTransform
geometry_msgs::msg::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const TimePoint &time) const override
Get the transform between two frames by frame ID.
tf2::BufferCore::_getParent
bool _getParent(const std::string &frame_id, TimePoint time, std::string &parent) const
Fill the parent of a frame.
tf2::BufferCore::TransformableCallback
std::function< void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, TimePoint time, TransformableResult result)> TransformableCallback
Definition: buffer_core.h:211
tf2::BufferCore::_lookupOrInsertFrameNumber
CompactFrameID _lookupOrInsertFrameNumber(const std::string &frameid_str)
Definition: buffer_core.h:260
visibility_control.h
tf2::TF2Error
TF2Error
Definition: exceptions.h:43
tf2::BufferCore
A Class which provides coordinate transforms between any two frames in a system.
Definition: buffer_core.h:89
tf2::BufferCore::clear
void clear() override
Clear all data.
tf2
Definition: buffer_core.h:53
TF2_PUBLIC
#define TF2_PUBLIC
Definition: visibility_control.h:57
std::mutex
tf2::BufferCore::~BufferCore
virtual ~BufferCore(void)
tf2::BufferCore::_getLatestCommonTime
tf2::TF2Error _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, TimePoint &time, std::string *error_string) const
Definition: buffer_core.h:266
std::unordered_map< std::string, CompactFrameID >
tf2::TransformableResult
TransformableResult
Definition: buffer_core.h:62
tf2::BufferCore::addTransformableRequest
TransformableRequestHandle addTransformableRequest(const TransformableCallback &cb, const std::string &target_frame, const std::string &source_frame, TimePoint time)
Internal use only.
tf2::TransformAvailable
@ TransformAvailable
Definition: buffer_core.h:64