tf2 rolling
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.
Loading...
Searching...
No Matches
buffer_core.hpp
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
34#ifndef TF2__BUFFER_CORE_HPP_
35#define TF2__BUFFER_CORE_HPP_
36
37#include <algorithm>
38#include <chrono>
39#include <cmath>
40#include <functional>
41#include <map>
42#include <memory>
43#include <mutex>
44#include <string>
45#include <unordered_map>
46#include <utility>
47#include <vector>
48
50#include "geometry_msgs/msg/transform_stamped.hpp"
51#include "geometry_msgs/msg/velocity_stamped.hpp"
53#include "tf2/exceptions.hpp"
56
57namespace tf2
58{
59
60typedef std::pair<TimePoint, CompactFrameID> P_TimeAndFrameID;
62
64using TimeCacheInterfacePtr = std::shared_ptr<TimeCacheInterface>;
65
71
73static constexpr Duration BUFFER_CORE_DEFAULT_CACHE_TIME = std::chrono::seconds(10);
74
94{
95public:
96 /************* Constants ***********************/
99 static const uint32_t MAX_GRAPH_DEPTH = 1000UL;
100
106 explicit BufferCore(tf2::Duration cache_time = BUFFER_CORE_DEFAULT_CACHE_TIME);
107
109 virtual ~BufferCore(void);
110
113 void clear() override;
114
123 const geometry_msgs::msg::TransformStamped & transform,
124 const std::string & authority, bool is_static = false);
125
126 /*********** Accessors *************/
127
138 geometry_msgs::msg::TransformStamped
140 const std::string & target_frame, const std::string & source_frame,
141 const TimePoint & time) const override;
142
156 geometry_msgs::msg::TransformStamped
158 const std::string & target_frame, const TimePoint & target_time,
159 const std::string & source_frame, const TimePoint & source_time,
160 const std::string & fixed_frame) const override;
161
163 geometry_msgs::msg::VelocityStamped lookupVelocity(
164 const std::string & tracking_frame, const std::string & observation_frame,
165 const TimePoint & time, const tf2::Duration & averaging_interval) const;
166
181 geometry_msgs::msg::VelocityStamped lookupVelocity(
182 const std::string & tracking_frame, const std::string & observation_frame,
183 const std::string & reference_frame, const tf2::Vector3 & reference_point,
184 const std::string & reference_point_frame,
185 const TimePoint & time, const tf2::Duration & duration) const;
186
196 const std::string & target_frame, const std::string & source_frame,
197 const TimePoint & time, std::string * error_msg = nullptr) const override;
198
210 const std::string & target_frame, const TimePoint & target_time,
211 const std::string & source_frame, const TimePoint & source_time,
212 const std::string & fixed_frame, std::string * error_msg = nullptr) const override;
213
217 std::vector<std::string> getAllFrameNames() const override;
218
223 std::string allFramesAsYAML(TimePoint current_time) const;
224
228 std::string allFramesAsYAML() const;
229
234 std::string allFramesAsString() const;
235
236 using TransformableCallback = std::function<
237 void (TransformableRequestHandle request_handle, const std::string & target_frame,
238 const std::string & source_frame,
239 TimePoint time, TransformableResult result)>;
240
244 const TransformableCallback & cb,
245 const std::string & target_frame,
246 const std::string & source_frame,
247 TimePoint time);
251
252
253 // Tell the buffer that there are multiple threads servicing it.
254 // This is useful for derived classes to know if they can block or not.
256 void setUsingDedicatedThread(bool value) {using_dedicated_thread_ = value;}
257 // Get the state of using_dedicated_thread_
259 bool isUsingDedicatedThread() const {return using_dedicated_thread_;}
260
261
262 /* Backwards compatability section for tf::Transformer you should not use these
263 */
264
268 bool _frameExists(const std::string & frame_id_str) const;
269
276 bool _getParent(const std::string & frame_id, TimePoint time, std::string & parent) const;
277
280 void _getFrameStrings(std::vector<std::string> & ids) const;
281
282
284 CompactFrameID _lookupFrameNumber(const std::string & frameid_str) const
285 {
286 return lookupFrameNumber(frameid_str);
287 }
289 CompactFrameID _lookupOrInsertFrameNumber(const std::string & frameid_str)
290 {
291 return lookupOrInsertFrameNumber(frameid_str);
292 }
293
296 CompactFrameID target_frame, CompactFrameID source_frame,
297 TimePoint & time, std::string * error_string) const
298 {
299 std::unique_lock<std::mutex> lock(frame_mutex_);
300 return getLatestCommonTime(target_frame, source_frame, time, error_string);
301 }
302
305 const char * function_name_arg,
306 const std::string & frame_id) const
307 {
308 return validateFrameId(function_name_arg, frame_id);
309 }
310
313 tf2::Duration getCacheLength() {return cache_time_;}
314
319 std::string _allFramesAsDot(TimePoint current_time) const;
321 std::string _allFramesAsDot() const;
322
328 const std::string & target_frame, TimePoint target_time,
329 const std::string & source_frame, TimePoint source_time,
330 const std::string & fixed_frame,
331 std::vector<std::string> & output) const;
332
333private:
334 /******************** Internal Storage ****************/
335
338 typedef std::vector<TimeCacheInterfacePtr> V_TimeCacheInterface;
339 V_TimeCacheInterface frames_;
340
342 mutable std::mutex frame_mutex_;
343
345 typedef std::unordered_map<std::string, CompactFrameID> M_StringToCompactFrameID;
346 M_StringToCompactFrameID frameIDs_;
348 std::vector<std::string> frameIDs_reverse_;
350 std::map<CompactFrameID, std::string> frame_authority_;
351
352
354 tf2::Duration cache_time_;
355
356 typedef uint32_t TransformableCallbackHandle;
357
358 typedef std::unordered_map<TransformableCallbackHandle,
359 TransformableCallback> M_TransformableCallback;
360 M_TransformableCallback transformable_callbacks_;
361 uint32_t transformable_callbacks_counter_;
362 std::mutex transformable_callbacks_mutex_;
363
364 struct TransformableRequest
365 {
366 TimePoint time;
367 TransformableRequestHandle request_handle;
368 TransformableCallbackHandle cb_handle;
369 CompactFrameID target_id;
370 CompactFrameID source_id;
371 std::string target_string;
372 std::string source_string;
373 };
374 typedef std::vector<TransformableRequest> V_TransformableRequest;
375 V_TransformableRequest transformable_requests_;
376 std::mutex transformable_requests_mutex_;
377 uint64_t transformable_requests_counter_;
378
379 bool using_dedicated_thread_;
380
381 /************************* Internal Functions ****************************/
382
386 std::string allFramesAsStringNoLock() const;
387
388 bool setTransformImpl(
389 const tf2::Vector3 & origin_in, const tf2::Quaternion & rotation_in,
390 const std::string & frame_id, const std::string & child_frame_id, const TimePoint stamp,
391 const std::string & authority, bool is_static);
392 void lookupTransformImpl(
393 const std::string & target_frame, const std::string & source_frame,
394 const TimePoint & time_in, tf2::Transform & transform_out, TimePoint & time_out) const;
395 void lookupTransformImpl(
396 const std::string & target_frame, const std::string & source_frame,
397 const TimePoint & time_in, tf2::Vector3 & origin_out, tf2::Quaternion & rotation_out,
398 TimePoint & time_out) const;
399
400 void lookupTransformImpl(
401 const std::string & target_frame, const TimePoint & target_time,
402 const std::string & source_frame, const TimePoint & source_time,
403 const std::string & fixed_frame, tf2::Transform & transform, TimePoint & time_out) const;
404
408 TimeCacheInterfacePtr getFrame(CompactFrameID c_frame_id) const;
409
410 TimeCacheInterfacePtr allocateFrame(CompactFrameID cfid, bool is_static);
411
421 CompactFrameID validateFrameId(
422 const char * function_name_arg,
423 const std::string & frame_id,
424 std::string * error_msg) const;
425
435 CompactFrameID validateFrameId(
436 const char * function_name_arg,
437 const std::string & frame_id) const;
438
440 CompactFrameID lookupFrameNumber(const std::string & frameid_str) const;
441
443 CompactFrameID lookupOrInsertFrameNumber(const std::string & frameid_str);
444
446 const std::string & lookupFrameString(CompactFrameID frame_id_num) const;
447
448 void createConnectivityErrorString(
449 CompactFrameID source_frame, CompactFrameID target_frame,
450 std::string * out) const;
451
454 tf2::TF2Error getLatestCommonTime(
455 CompactFrameID target_frame, CompactFrameID source_frame,
456 TimePoint & time, std::string * error_string) const;
457
460 template<typename F>
461 tf2::TF2Error walkToTopParent(
462 F & f, TimePoint time, CompactFrameID target_id,
463 CompactFrameID source_id, std::string * error_string,
464 std::vector<CompactFrameID> * frame_chain) const;
465
466 void testTransformableRequests();
467
468 // Actual implementation to walk the transform tree and find out if a transform exists.
469 bool canTransformInternal(
470 CompactFrameID target_id, CompactFrameID source_id,
471 const TimePoint & time, std::string * error_msg) const;
472};
473} // namespace tf2
474
475#endif // TF2__BUFFER_CORE_HPP_
Interface for providing coordinate transforms between any two frames in a system.
Definition buffer_core_interface.hpp:49
A Class which provides coordinate transforms between any two frames in a system.
Definition buffer_core.hpp:94
bool isUsingDedicatedThread() const
Definition buffer_core.hpp:259
void clear() override
Clear all data.
tf2::Duration getCacheLength()
Get the duration over which this transformer will cache.
Definition buffer_core.hpp:313
bool canTransform(const std::string &target_frame, const std::string &source_frame, const TimePoint &time, std::string *error_msg=nullptr) const override
Test if a transform is possible.
void setUsingDedicatedThread(bool value)
Definition buffer_core.hpp:256
CompactFrameID _lookupOrInsertFrameNumber(const std::string &frameid_str)
Definition buffer_core.hpp:289
void _getFrameStrings(std::vector< std::string > &ids) const
A way to get a std::vector of available frame ids.
geometry_msgs::msg::VelocityStamped lookupVelocity(const std::string &tracking_frame, const std::string &observation_frame, const std::string &reference_frame, const tf2::Vector3 &reference_point, const std::string &reference_point_frame, const TimePoint &time, const tf2::Duration &duration) const
Lookup the velocity of the tracking_frame with respect to the observation frame in the reference_fram...
bool setTransform(const geometry_msgs::msg::TransformStamped &transform, const std::string &authority, bool is_static=false)
Add transform information to the tf data structure.
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.
bool canTransform(const std::string &target_frame, const TimePoint &target_time, const std::string &source_frame, const TimePoint &source_time, const std::string &fixed_frame, std::string *error_msg=nullptr) const override
Test if a transform is possible.
std::string _allFramesAsDot(TimePoint current_time) const
Backwards compatabilityA way to see what frames have been cached Useful for debugging.
virtual ~BufferCore(void)
static const uint32_t MAX_GRAPH_DEPTH
< Maximum graph search depth (deeper graphs will be assumed to have loops)
Definition buffer_core.hpp:99
geometry_msgs::msg::TransformStamped lookupTransform(const std::string &target_frame, const TimePoint &target_time, const std::string &source_frame, const TimePoint &source_time, const std::string &fixed_frame) const override
Get the transform between two frames by frame ID assuming fixed frame.
BufferCore(tf2::Duration cache_time=BUFFER_CORE_DEFAULT_CACHE_TIME)
CompactFrameID _lookupFrameNumber(const std::string &frameid_str) const
Definition buffer_core.hpp:284
tf2::TF2Error _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, TimePoint &time, std::string *error_string) const
Definition buffer_core.hpp:295
std::string allFramesAsYAML() const
std::function< void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, TimePoint time, TransformableResult result)> TransformableCallback
Definition buffer_core.hpp:239
void cancelTransformableRequest(TransformableRequestHandle handle)
Internal use only.
std::string _allFramesAsDot() const
geometry_msgs::msg::VelocityStamped lookupVelocity(const std::string &tracking_frame, const std::string &observation_frame, const TimePoint &time, const tf2::Duration &averaging_interval) const
std::string allFramesAsYAML(TimePoint current_time) const
A way to see what frames have been cached in yaml format Useful for debugging tools.
bool _frameExists(const std::string &frame_id_str) const
Check if a frame exists in the tree.
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.
TransformableRequestHandle addTransformableRequest(const TransformableCallback &cb, const std::string &target_frame, const std::string &source_frame, TimePoint time)
Internal use only.
CompactFrameID _validateFrameId(const char *function_name_arg, const std::string &frame_id) const
Definition buffer_core.hpp:304
std::string allFramesAsString() const
A way to see what frames have been cached Useful for debugging.
bool _getParent(const std::string &frame_id, TimePoint time, std::string &parent) const
Fill the parent of a frame.
std::vector< std::string > getAllFrameNames() const override
Get all frames that exist in the system.
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x...
Definition Quaternion.hpp:30
Definition time_cache.hpp:53
The Transform class supports rigid transforms with only translation and rotation and no scaling/shear...
Definition Transform.hpp:33
tf2::Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16...
Definition Vector3.hpp:40
Author: Tully Foote.
Definition buffer_core.hpp:58
uint64_t TransformableRequestHandle
Definition buffer_core.hpp:61
uint32_t CompactFrameID
Definition transform_storage.hpp:44
std::pair< TimePoint, CompactFrameID > P_TimeAndFrameID
Definition buffer_core.hpp:60
TF2Error
Definition exceptions.hpp:46
std::chrono::time_point< std::chrono::system_clock, Duration > TimePoint
Definition time.hpp:41
std::chrono::nanoseconds Duration
Definition time.hpp:40
std::shared_ptr< TimeCacheInterface > TimeCacheInterfacePtr
Definition buffer_core.hpp:64
TransformableResult
Definition buffer_core.hpp:67
@ TransformAvailable
Definition buffer_core.hpp:68
@ TransformFailure
Definition buffer_core.hpp:69
Author: Tully Foote.
#define TF2_PUBLIC
Definition visibility_control.h:57