Public Member Functions | Private Attributes | List of all members
cras::NodeletWithSharedTfBuffer< NodeletType > Struct Template Reference

A nodelet mixin that allows to use a tf2_ros::Buffer provided by the nodelet manager (which should save some computations). If this nodelet has also the StatefulNodelet mixin, the automatically created non-shared buffer is nodelet-aware (you can also pass a NodeletAwareTfBuffer to setBuffer()). That means any TF lookups done via this->getBuffer() will be able to correctly end when the nodelet is being unloaded (which normally hangs: https://github.com/ros/geometry2/issues/381). More...

#include <nodelet_with_shared_tf_buffer.hpp>

Inheritance diagram for cras::NodeletWithSharedTfBuffer< NodeletType >:
Inheritance graph
[legend]

Public Member Functions

::cras::NodeletAwareTFBuffergetBuffer () const override
 Get the TF buffer used by the nodelet. If none has been set by setBuffer(), a buffer is automatically created. More...
 
 NodeletWithSharedTfBuffer ()
 
virtual void onInit ()
 
void reset () override
 Reset the TF buffer. If a shared buffer is used, it is not reset by this call and its owner is responsible. More...
 
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 created. More...
 
bool usesSharedBuffer () const override
 Whether the buffer set using setBuffer() is used or a standalone buffer has been automatically created. More...
 
virtual ~NodeletWithSharedTfBuffer ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Attributes

::std::unique_ptr<::cras::impl::NodeletWithSharedTfBufferPrivate > data
 PIMPL. More...
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Member Functions inherited from cras::TimeJumpResettable
void checkTimeJump ()
 Check if ROS time has not jumped back. If it did, call reset(). More...
 
virtual void checkTimeJump (const ::ros::Time &now)
 Check if ROS time has not jumped back. If it did, call reset(). More...
 
void initRos (const ::ros::NodeHandle &pnh) override
 Initialize the ROS part of the interface - subscriber to /reset and ~reset topics, read time jump limits. More...
 
void startAutoCheckTimeJump ()
 Start a background 1 Hz timer that automatically checks for time jumps. More...
 
virtual void startAutoCheckTimeJump (const ::ros::WallRate &rate)
 Start a background timer that automatically checks for time jumps. More...
 
virtual void stopAutoCheckTimeJump ()
 Stop the timer that automatically checks for time jumps. More...
 
 TimeJumpResettable (const ::cras::LogHelperPtr &log)
 Create the resettable interface. To also wire up to the reset topics and time jump resets, call initRos(). More...
 
 ~TimeJumpResettable () override
 
- Protected Member Functions inherited from cras::Resettable
 Resettable (const ::cras::LogHelperPtr &log)
 Create the resettable interface. To also wire up to the reset topics, call initRos(). More...
 
virtual ~Resettable ()
 

Detailed Description

template<typename NodeletType = ::nodelet::Nodelet>
struct cras::NodeletWithSharedTfBuffer< NodeletType >

A nodelet mixin that allows to use a tf2_ros::Buffer provided by the nodelet manager (which should save some computations). If this nodelet has also the StatefulNodelet mixin, the automatically created non-shared buffer is nodelet-aware (you can also pass a NodeletAwareTfBuffer to setBuffer()). That means any TF lookups done via this->getBuffer() will be able to correctly end when the nodelet is being unloaded (which normally hangs: https://github.com/ros/geometry2/issues/381).

Template Parameters
NodeletTypeType of the base nodelet.

Definition at line 75 of file nodelet_with_shared_tf_buffer.hpp.

Constructor & Destructor Documentation

◆ NodeletWithSharedTfBuffer()

template<typename NodeletType = ::nodelet::Nodelet>
cras::NodeletWithSharedTfBuffer< NodeletType >::NodeletWithSharedTfBuffer ( )

◆ ~NodeletWithSharedTfBuffer()

template<typename NodeletType = ::nodelet::Nodelet>
virtual cras::NodeletWithSharedTfBuffer< NodeletType >::~NodeletWithSharedTfBuffer ( )
virtual

Member Function Documentation

◆ getBuffer()

template<typename NodeletType = ::nodelet::Nodelet>
::cras::NodeletAwareTFBuffer& cras::NodeletWithSharedTfBuffer< NodeletType >::getBuffer ( ) const
overridevirtual

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.

Implements cras::NodeletWithSharedTfBufferInterface.

◆ onInit()

template<typename NodeletType = ::nodelet::Nodelet>
virtual void cras::NodeletWithSharedTfBuffer< NodeletType >::onInit ( )
virtual

◆ reset()

template<typename NodeletType = ::nodelet::Nodelet>
void cras::NodeletWithSharedTfBuffer< NodeletType >::reset ( )
overridevirtual

Reset the TF buffer. If a shared buffer is used, it is not reset by this call and its owner is responsible.

Implements cras::NodeletWithSharedTfBufferInterface.

◆ setBuffer()

template<typename NodeletType = ::nodelet::Nodelet>
void cras::NodeletWithSharedTfBuffer< NodeletType >::setBuffer ( const ::std::shared_ptr<::tf2_ros::Buffer > &  buffer)
overridevirtual

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.

Implements cras::NodeletWithSharedTfBufferInterface.

◆ usesSharedBuffer()

template<typename NodeletType = ::nodelet::Nodelet>
bool cras::NodeletWithSharedTfBuffer< NodeletType >::usesSharedBuffer ( ) const
overridevirtual

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.

Implements cras::NodeletWithSharedTfBufferInterface.

Member Data Documentation

◆ data

template<typename NodeletType = ::nodelet::Nodelet>
::std::unique_ptr<::cras::impl::NodeletWithSharedTfBufferPrivate> cras::NodeletWithSharedTfBuffer< NodeletType >::data
private

PIMPL.

Definition at line 95 of file nodelet_with_shared_tf_buffer.hpp.


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


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Mar 2 2024 03:47:35