Class BufferCoreInterface
- Defined in File buffer_core_interface.h 
Inheritance Relationships
Derived Type
- public tf2::BufferCore(Class BufferCore)
Class Documentation
- 
class BufferCoreInterface
- Interface for providing coordinate transforms between any two frames in a system. - This class provides a simple abstract interface for looking up relationships between arbitrary frames of a system. - Subclassed by tf2::BufferCore - Public Functions - 
virtual ~BufferCoreInterface() = default
 - 
virtual void clear() = 0
- Clear internal state data. 
 - 
virtual geometry_msgs::msg::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time) const = 0
- Get the transform between two frames by frame ID. - 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 tf2::TimePoint &target_time, const std::string &source_frame, const tf2::TimePoint &source_time, const std::string &fixed_frame) const = 0
- Get the transform between two frames by frame ID assuming fixed frame. - 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. 
 
 - 
virtual bool canTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, std::string *error_msg) const = 0
- 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. Ignored if nullptr. 
 
- Returns:
- true if the transform is possible, false otherwise. 
 
 - 
virtual bool canTransform(const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &source_frame, const tf2::TimePoint &source_time, const std::string &fixed_frame, std::string *error_msg) const = 0
- 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. Ignored if nullptr. 
 
- Returns:
- true if the transform is possible, false otherwise. 
 
 - 
virtual std::vector<std::string> getAllFrameNames() const = 0
- Get all frames that exist in the system. - Returns:
- all frame names in a vector. 
 
 
- 
virtual ~BufferCoreInterface() = default