Go to the documentation of this file.
29 struct NodeletWithSharedTfBufferPrivate;
43 virtual void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer>& buffer) = 0;
53 virtual ::cras::NodeletAwareTFBuffer&
getBuffer()
const = 0;
64 virtual void reset() = 0;
75 template <
typename NodeletType = ::nodelet::Nodelet>
83 void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer>& buffer)
override;
85 ::std::shared_ptr<::cras::NodeletAwareTFBuffer>
getBufferPtr()
const;
90 void reset()
override;
93 using NodeletType::getName;
97 ::std::unique_ptr<::cras::impl::NodeletWithSharedTfBufferPrivate>
data;
102 #include "impl/nodelet_with_shared_tf_buffer.hpp"
NodeletWithSharedTfBuffer()
virtual bool usesSharedBuffer() const =0
Whether the buffer set using setBuffer() is used or a standalone buffer has been automatically create...
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 cre...
void reset() override
Reset the TF buffer. If a shared buffer is used, it is not reset by this call and its owner is respon...
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...
::cras::NodeletAwareTFBuffer & getBuffer() const override
Get the TF buffer used by the nodelet. If none has been set by setBuffer(), a buffer is automatically...
TF buffer that can be correctly interrupted by nodelet unload.
::std::unique_ptr<::cras::impl::NodeletWithSharedTfBufferPrivate > data
PIMPL.
Public non-template API of NodeletWithSharedTfBuffer. Dynamic_cast a nodelet to this type if you need...
bool usesSharedBuffer() const override
Whether the buffer set using setBuffer() is used or a standalone buffer has been automatically create...
Interface for resettable nodes and nodelets. Automatic reset on time jumps.
void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer > &buffer) override
Set the TF buffer to be used by the nodelet. If this method is not called, a standalone buffer is cre...
~NodeletWithSharedTfBuffer() override
::std::shared_ptr<::cras::NodeletAwareTFBuffer > getBufferPtr() const
A nodelet mixin that allows to use a tf2_ros::Buffer provided by the nodelet manager (which should sa...
Interface for resettable nodes and nodelets. Automatic reset on time jumps.
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 respon...
cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Dec 14 2024 03:51:04