34#ifndef TF2__BUFFER_CORE_HPP_
35#define TF2__BUFFER_CORE_HPP_
45#include <unordered_map>
50#include "geometry_msgs/msg/transform_stamped.hpp"
51#include "geometry_msgs/msg/velocity_stamped.hpp"
73static constexpr Duration BUFFER_CORE_DEFAULT_CACHE_TIME = std::chrono::seconds(10);
123 const geometry_msgs::msg::TransformStamped & transform,
124 const std::string & authority,
bool is_static =
false);
138 geometry_msgs::msg::TransformStamped
140 const std::string & target_frame,
const std::string & source_frame,
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;
164 const std::string & tracking_frame,
const std::string & observation_frame,
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,
196 const std::string & target_frame,
const std::string & source_frame,
197 const TimePoint & time, std::string * error_msg =
nullptr)
const override;
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;
238 const std::string & source_frame,
245 const std::string & target_frame,
246 const std::string & source_frame,
286 return lookupFrameNumber(frameid_str);
291 return lookupOrInsertFrameNumber(frameid_str);
297 TimePoint & time, std::string * error_string)
const
299 std::unique_lock<std::mutex> lock(frame_mutex_);
300 return getLatestCommonTime(target_frame, source_frame, time, error_string);
305 const char * function_name_arg,
306 const std::string & frame_id)
const
308 return validateFrameId(function_name_arg, frame_id);
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;
338 typedef std::vector<TimeCacheInterfacePtr> V_TimeCacheInterface;
339 V_TimeCacheInterface frames_;
342 mutable std::mutex frame_mutex_;
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_;
356 typedef uint32_t TransformableCallbackHandle;
358 typedef std::unordered_map<TransformableCallbackHandle,
360 M_TransformableCallback transformable_callbacks_;
361 uint32_t transformable_callbacks_counter_;
362 std::mutex transformable_callbacks_mutex_;
364 struct TransformableRequest
368 TransformableCallbackHandle cb_handle;
371 std::string target_string;
372 std::string source_string;
374 typedef std::vector<TransformableRequest> V_TransformableRequest;
375 V_TransformableRequest transformable_requests_;
376 std::mutex transformable_requests_mutex_;
377 uint64_t transformable_requests_counter_;
379 bool using_dedicated_thread_;
386 std::string allFramesAsStringNoLock()
const;
388 bool setTransformImpl(
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,
395 void lookupTransformImpl(
396 const std::string & target_frame,
const std::string & source_frame,
400 void lookupTransformImpl(
401 const std::string & target_frame,
const TimePoint & target_time,
402 const std::string & source_frame,
const TimePoint & source_time,
422 const char * function_name_arg,
423 const std::string & frame_id,
424 std::string * error_msg)
const;
436 const char * function_name_arg,
437 const std::string & frame_id)
const;
440 CompactFrameID lookupFrameNumber(
const std::string & frameid_str)
const;
443 CompactFrameID lookupOrInsertFrameNumber(
const std::string & frameid_str);
446 const std::string & lookupFrameString(
CompactFrameID frame_id_num)
const;
448 void createConnectivityErrorString(
450 std::string * out)
const;
456 TimePoint & time, std::string * error_string)
const;
464 std::vector<CompactFrameID> * frame_chain)
const;
466 void testTransformableRequests();
469 bool canTransformInternal(
471 const TimePoint & time, std::string * error_msg)
const;
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
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
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
#define TF2_PUBLIC
Definition visibility_control.h:57