Class BufferCore
Defined in File buffer_core.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public tf2::BufferCoreInterface
(Class BufferCoreInterface)
Class Documentation
-
class BufferCore : public tf2::BufferCoreInterface
A Class which provides coordinate transforms between any two frames in a system.
This class provides a simple interface to allow recording and lookup of relationships between arbitrary frames of the system.
libTF assumes that there is a tree of coordinate frame transforms which define the relationship between all coordinate frames. For example your typical robot would have a transform from global to real world. And then from base to hand, and from base to head. But Base to Hand really is composed of base to shoulder to elbow to wrist to hand. libTF is designed to take care of all the intermediate steps for you.
Internal Representation libTF will store frames with the parameters necessary for generating the transform into that frame from it’s parent and a reference to the parent frame. Frames are designated using an std::string 0 is a frame without a parent (the top of a tree) The positions of frames over time must be pushed in.
All function calls which pass frame ids can potentially throw the exception tf::LookupException
Public Types
-
using TransformableCallback = std::function<void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, TimePoint time, TransformableResult result)>
Public Functions
-
explicit BufferCore(tf2::Duration cache_time_ = BUFFER_CORE_DEFAULT_CACHE_TIME)
Constructor
- Parameters:
interpolating – Whether to interpolate, if this is false the closest value will be returned
cache_time – How long to keep a history of transforms in nanoseconds
-
virtual ~BufferCore(void)
-
virtual void clear() override
Clear all data.
-
bool setTransform(const geometry_msgs::msg::TransformStamped &transform, const std::string &authority, bool is_static = false)
Add transform information to the tf data structure.
- Parameters:
transform – The transform to store
authority – The source of the information for this transform
is_static – Record this transform as a static transform. It will be good across all time. (This cannot be changed after the first call.)
- Returns:
True unless an error occured
-
virtual 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.
Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException
- Parameters:
target_frame – The frame to which data should be transformed
source_frame – The frame where the data originated
time – The time at which the value of the transform is desired. (0 will get the latest)
- Returns:
The transform between the frames
-
virtual 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.
Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException
- Parameters:
target_frame – The frame to which data should be transformed
target_time – The time to which the data should be transformed. (0 will get the latest)
source_frame – The frame where the data originated
source_time – The time at which the source_frame should be evaluated. (0 will get the latest)
fixed_frame – The frame in which to assume the transform is constant in time.
- Returns:
The transform between the frames
-
geometry_msgs::msg::VelocityStamped lookupVelocity(const std::string &tracking_frame, const std::string &observation_frame, const TimePoint &time, const tf2::Duration &averaging_interval) const
-
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 moving_frame in the reference_frame.
Possible exceptions TransformReference::LookupException, TransformReference::ConnectivityException, TransformReference::MaxDepthException
- Parameters:
reference_frame – The frame in which to track
moving_frame – The frame to track
time – The time at which to get the velocity
duration – The period over which to average
velocity – The velocity output
-
virtual 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.
- Parameters:
target_frame – The frame into which to transform
source_frame – The frame from which to transform
time – The time at which to transform
error_msg – A pointer to a string which will be filled with why the transform failed, if not nullptr
- Returns:
True if the transform is possible, false otherwise
-
virtual 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.
- Parameters:
target_frame – The frame into which to transform
target_time – The time into which to transform
source_frame – The frame from which to transform
source_time – The time from which to transform
fixed_frame – The frame in which to treat the transform as constant in time
error_msg – A pointer to a string which will be filled with why the transform failed, if not nullptr
- Returns:
True if the transform is possible, false otherwise
-
virtual std::vector<std::string> getAllFrameNames() const override
Get all frames that exist in the system.
-
std::string allFramesAsYAML(TimePoint current_time) const
A way to see what frames have been cached in yaml format Useful for debugging tools.
-
std::string allFramesAsYAML() const
Backwards compatibility for #84
-
std::string allFramesAsString() const
A way to see what frames have been cached Useful for debugging.
-
TransformableRequestHandle addTransformableRequest(const TransformableCallback &cb, const std::string &target_frame, const std::string &source_frame, TimePoint time)
Internal use only.
-
void cancelTransformableRequest(TransformableRequestHandle handle)
Internal use only.
-
inline void setUsingDedicatedThread(bool value)
-
inline bool isUsingDedicatedThread() const
-
bool _frameExists(const std::string &frame_id_str) const
Check if a frame exists in the tree.
- Parameters:
frame_id_str – The frame id in question
-
bool _getParent(const std::string &frame_id, TimePoint time, std::string &parent) const
Fill the parent of a frame.
- Parameters:
frame_id – The frame id of the frame in question
parent – The reference to the string to fill the parent Returns true unless “NO_PARENT”
-
void _getFrameStrings(std::vector<std::string> &ids) const
A way to get a std::vector of available frame ids.
-
inline CompactFrameID _lookupFrameNumber(const std::string &frameid_str) const
-
inline CompactFrameID _lookupOrInsertFrameNumber(const std::string &frameid_str)
-
inline tf2::TF2Error _getLatestCommonTime(CompactFrameID target_frame, CompactFrameID source_frame, TimePoint &time, std::string *error_string) const
-
inline CompactFrameID _validateFrameId(const char *function_name_arg, const std::string &frame_id) const
-
std::string _allFramesAsDot(TimePoint current_time) const
Backwards compatabilityA way to see what frames have been cached Useful for debugging.
-
std::string _allFramesAsDot() const
Public Static Attributes
-
static const uint32_t MAX_GRAPH_DEPTH = 1000UL
< Maximum graph search depth (deeper graphs will be assumed to have loops)
-
using TransformableCallback = std::function<void(TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, TimePoint time, TransformableResult result)>