Struct NodeletWithSharedTfBufferInterface
Defined in File nodelet_with_shared_tf_buffer.hpp
Inheritance Relationships
Derived Types
public cras::NodeletWithSharedTfBuffer< ::nodelet::Nodelet >(Template Struct NodeletWithSharedTfBuffer)public cras::NodeletWithSharedTfBuffer< BaseNodelet >(Template Struct NodeletWithSharedTfBuffer)public cras::NodeletWithSharedTfBuffer< NodeletType >(Template Struct NodeletWithSharedTfBuffer)
Struct Documentation
-
struct NodeletWithSharedTfBufferInterface
Public non-template API of NodeletWithSharedTfBuffer. Dynamic_cast a nodelet to this type if you need to access this API publicly.
Subclassed by cras::NodeletWithSharedTfBuffer< ::nodelet::Nodelet >, cras::NodeletWithSharedTfBuffer< BaseNodelet >, cras::NodeletWithSharedTfBuffer< NodeletType >
Public Functions
-
virtual void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer> &buffer) = 0
Set the TF buffer to be used by the nodelet. If this method is not called, a standalone buffer is created.
- Parameters:
buffer – [in] The buffer to use.
-
virtual ::cras::NodeletAwareTFBuffer &getBuffer() const = 0
Get the TF buffer used by the nodelet. If none has been set by
setBuffer(), a buffer is automatically created.Note
This buffer only offers the timeouting versions of canTransform() and lookupTransform(). It does not offer setTransform() and many other functions. User getRawBuffer() on the returned instance to get a tf2::BufferCore that offers the missing non-time-aware functionality.
- Returns:
The buffer.
-
virtual bool usesSharedBuffer() const = 0
Whether the buffer set using
setBuffer()is used or a standalone buffer has been automatically created.- Returns:
Whether the buffer set using
setBuffer()is used or a standalone buffer has been automatically created.
-
virtual void reset() = 0
Reset the TF buffer. If a shared buffer is used, it is not reset by this call and its owner is responsible.
-
virtual void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer> &buffer) = 0