LocalGuidance
A library that generates velocity references to follow a path.
any_node::Nodewrap< NodeImpl > Class Template Reference

#include <Nodewrap.hpp>

Public Member Functions

 Nodewrap ()=delete
 
 Nodewrap (int argc, char **argv, const std::string &nodeName, int numSpinners=-1, const bool installSignalHandler=true)
 
virtual ~Nodewrap ()=default
 
void execute ()
 
bool init ()
 
void run ()
 
void cleanup ()
 
void stop ()
 
void signalHandler (const int signum)
 INTERNAL FUNCTIONS. More...
 
NodeImpl * getImplPtr ()
 

Static Public Member Functions

static void checkSteadyClock ()
 

Protected Attributes

std::shared_ptr< ros::NodeHandle > nh_
 
std::unique_ptr< ros::AsyncSpinner > spinner_
 
std::unique_ptr< NodeImpl > impl_
 
bool signalHandlerInstalled_
 
std::atomic< bool > running_
 
std::condition_variable cvRunning_
 
std::mutex mutexRunning_
 

Constructor & Destructor Documentation

template<class NodeImpl >
any_node::Nodewrap< NodeImpl >::Nodewrap ( )
delete
template<class NodeImpl >
any_node::Nodewrap< NodeImpl >::Nodewrap ( int  argc,
char **  argv,
const std::string &  nodeName,
int  numSpinners = -1,
const bool  installSignalHandler = true 
)
inline
Parameters
argc
argv
nodeNamename of the node
numSpinnersnumber of async ros spinners. Set to -1 to get value from ros params. A value of 0 means to use the number of processor cores.
installSignalHandlerset to False to use the ros internal signal handler instead
template<class NodeImpl >
virtual any_node::Nodewrap< NodeImpl >::~Nodewrap ( )
virtualdefault

Member Function Documentation

template<class NodeImpl >
static void any_node::Nodewrap< NodeImpl >::checkSteadyClock ( )
inlinestatic
template<class NodeImpl >
void any_node::Nodewrap< NodeImpl >::cleanup ( )
inline

Stops the workers, ros spinners and calls cleanup of the underlying instance of any_node::Node

template<class NodeImpl >
void any_node::Nodewrap< NodeImpl >::execute ( )
inline

blocking call, executes init, run and cleanup

template<class NodeImpl >
NodeImpl* any_node::Nodewrap< NodeImpl >::getImplPtr ( )
inline
template<class NodeImpl >
bool any_node::Nodewrap< NodeImpl >::init ( )
inline

Initializes the node

template<class NodeImpl >
void any_node::Nodewrap< NodeImpl >::run ( )
inline

blocking call, returns when the program should shut down

template<class NodeImpl >
void any_node::Nodewrap< NodeImpl >::signalHandler ( const int  signum)
inline

INTERNAL FUNCTIONS.

template<class NodeImpl >
void any_node::Nodewrap< NodeImpl >::stop ( )
inline

Stops execution of the run(..) function.

Member Data Documentation

template<class NodeImpl >
std::condition_variable any_node::Nodewrap< NodeImpl >::cvRunning_
protected
template<class NodeImpl >
std::unique_ptr<NodeImpl> any_node::Nodewrap< NodeImpl >::impl_
protected
template<class NodeImpl >
std::mutex any_node::Nodewrap< NodeImpl >::mutexRunning_
protected
template<class NodeImpl >
std::shared_ptr<ros::NodeHandle> any_node::Nodewrap< NodeImpl >::nh_
protected
template<class NodeImpl >
std::atomic<bool> any_node::Nodewrap< NodeImpl >::running_
protected
template<class NodeImpl >
bool any_node::Nodewrap< NodeImpl >::signalHandlerInstalled_
protected
template<class NodeImpl >
std::unique_ptr<ros::AsyncSpinner> any_node::Nodewrap< NodeImpl >::spinner_
protected

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