Public Member Functions | List of all members
cras::NodeletWithSharedTfBufferInterface Struct Referenceabstract

Public non-template API of NodeletWithSharedTfBuffer. Dynamic_cast a nodelet to this type if you need to access this API publicly. More...

#include <nodelet_with_shared_tf_buffer.hpp>

Inheritance diagram for cras::NodeletWithSharedTfBufferInterface:
Inheritance graph
[legend]

Public Member Functions

virtual ::cras::NodeletAwareTFBuffergetBuffer () const =0
 Get the TF buffer used by the nodelet. If none has been set by setBuffer(), a buffer is automatically created. More...
 
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. More...
 
virtual bool usesSharedBuffer () const =0
 Whether the buffer set using setBuffer() is used or a standalone buffer has been automatically created. More...
 

Detailed Description

Public non-template API of NodeletWithSharedTfBuffer. Dynamic_cast a nodelet to this type if you need to access this API publicly.

Definition at line 34 of file nodelet_with_shared_tf_buffer.hpp.

Member Function Documentation

◆ getBuffer()

virtual ::cras::NodeletAwareTFBuffer& cras::NodeletWithSharedTfBufferInterface::getBuffer ( ) const
pure virtual

Get the TF buffer used by the nodelet. If none has been set by setBuffer(), a buffer is automatically created.

Returns
The buffer.
Note
This buffer is 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.

Implemented in cras::NodeletWithSharedTfBuffer< NodeletType >, cras::NodeletWithSharedTfBuffer< BaseNodelet >, and cras::NodeletWithSharedTfBuffer< ::nodelet::Nodelet >.

◆ setBuffer()

virtual void cras::NodeletWithSharedTfBufferInterface::setBuffer ( const ::std::shared_ptr<::tf2_ros::Buffer > &  buffer)
pure virtual

Set the TF buffer to be used by the nodelet. If this method is not called, a standalone buffer is created.

Parameters
[in]bufferThe buffer to use.

Implemented in cras::NodeletWithSharedTfBuffer< NodeletType >, cras::NodeletWithSharedTfBuffer< BaseNodelet >, and cras::NodeletWithSharedTfBuffer< ::nodelet::Nodelet >.

◆ usesSharedBuffer()

virtual bool cras::NodeletWithSharedTfBufferInterface::usesSharedBuffer ( ) const
pure virtual

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.

Implemented in cras::NodeletWithSharedTfBuffer< NodeletType >, cras::NodeletWithSharedTfBuffer< BaseNodelet >, and cras::NodeletWithSharedTfBuffer< ::nodelet::Nodelet >.


The documentation for this struct was generated from the following file:


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:32:53