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>
Public Member Functions | |
::cras::NodeletAwareTFBuffer & | getBuffer () 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::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () 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 () |
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).
NodeletType | Type of the base nodelet. |
Definition at line 75 of file nodelet_with_shared_tf_buffer.hpp.
cras::NodeletWithSharedTfBuffer< NodeletType >::NodeletWithSharedTfBuffer | ( | ) |
|
virtual |
|
overridevirtual |
Get the TF buffer used by the nodelet. If none has been set by setBuffer()
, a buffer is automatically created.
Implements cras::NodeletWithSharedTfBufferInterface.
|
virtual |
Implements nodelet::Nodelet.
Reimplemented in cras::FilterChainNodelet< F >, cras::NodeletBase< BaseNodelet >, and cras::NodeletBase<::nodelet::Nodelet >.
|
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.
|
overridevirtual |
Set the TF buffer to be used by the nodelet. If this method is not called, a standalone buffer is created.
[in] | buffer | The buffer to use. |
Implements cras::NodeletWithSharedTfBufferInterface.
|
overridevirtual |
Whether the buffer set using setBuffer()
is used or a standalone buffer has been automatically created.
setBuffer()
is used or a standalone buffer has been automatically created. Implements cras::NodeletWithSharedTfBufferInterface.
|
private |
PIMPL.
Definition at line 95 of file nodelet_with_shared_tf_buffer.hpp.