Public Types | Public Member Functions | Protected Attributes | Private Attributes | List of all members
bota_node::Node Class Referenceabstract

#include <Node.hpp>

Public Types

using NodeHandlePtr = std::shared_ptr< ros::NodeHandle >
 

Public Member Functions

template<class T >
bool addWorker (const std::string &name, const double timestep, bool(T::*fp)(const bota_worker::WorkerEvent &), T *obj, const int priority=0)
 
bool addWorker (const bota_worker::WorkerOptions &options)
 
void cancelWorker (const std::string &name, const bool wait=true)
 
virtual void cleanup ()=0
 
ros::NodeHandlegetNodeHandle () const
 
bool hasWorker (const std::string &name)
 
virtual bool init ()=0
 
 Node ()=delete
 
 Node (NodeHandlePtr nh)
 
virtual void preCleanup ()
 
void shutdown ()
 
void stopAllWorkers ()
 
void stopAllWorkers (bool wait)
 
virtual ~Node ()=default
 

Protected Attributes

NodeHandlePtr nh_
 

Private Attributes

bota_worker::WorkerManager workerManager_
 

Detailed Description

Definition at line 21 of file Node.hpp.

Member Typedef Documentation

Definition at line 24 of file Node.hpp.

Constructor & Destructor Documentation

bota_node::Node::Node ( )
delete
bota_node::Node::Node ( NodeHandlePtr  nh)
explicit

Definition at line 13 of file Node.cpp.

virtual bota_node::Node::~Node ( )
virtualdefault

Member Function Documentation

template<class T >
bool bota_node::Node::addWorker ( const std::string &  name,
const double  timestep,
bool(T::*)(const bota_worker::WorkerEvent &)  fp,
T *  obj,
const int  priority = 0 
)
inline

Helper functions to add Workers to the WorkerManager

Definition at line 65 of file Node.hpp.

bool bota_node::Node::addWorker ( const bota_worker::WorkerOptions options)
inline

Definition at line 71 of file Node.hpp.

void bota_node::Node::cancelWorker ( const std::string &  name,
const bool  wait = true 
)
inline

Stop a worker managed by the WorkerManager

Parameters
nameName of the worker
waitWhether to wait until the worker has finished or return immediately

Definition at line 91 of file Node.hpp.

virtual void bota_node::Node::cleanup ( )
pure virtual

Cleanup function, called by Nodewrap after stopping workers. This function is called even if init() returned false.

ros::NodeHandle& bota_node::Node::getNodeHandle ( ) const
inline

Definition at line 111 of file Node.hpp.

bool bota_node::Node::hasWorker ( const std::string &  name)
inline

Check if WorkerManager is managing a Worker with given name

Parameters
nameName of the worker
Returns
True if worker was found

Definition at line 81 of file Node.hpp.

virtual bool bota_node::Node::init ( )
pure virtual

Init function, used to initialize all members and starting workers (if any).

Returns
True if successful. Returning false indicates that the node shall shut down.
virtual void bota_node::Node::preCleanup ( )
inlinevirtual

Pre-Cleanup function, which is called by Nodewrap before stopping workers. (Thread safety up to the user!). This function is called even if init() returned false.

Definition at line 43 of file Node.hpp.

void bota_node::Node::shutdown ( )

Method to signal nodewrap to shutdown the node.

Definition at line 17 of file Node.cpp.

void bota_node::Node::stopAllWorkers ( )
inline

Method to stop all workers managed by the WorkerManager

Definition at line 99 of file Node.hpp.

void bota_node::Node::stopAllWorkers ( bool  wait)
inline

Definition at line 103 of file Node.hpp.

Member Data Documentation

NodeHandlePtr bota_node::Node::nh_
protected

Definition at line 117 of file Node.hpp.

bota_worker::WorkerManager bota_node::Node::workerManager_
private

Definition at line 120 of file Node.hpp.


The documentation for this class was generated from the following files:


bota_node
Author(s):
autogenerated on Wed Mar 3 2021 03:09:11