23 #include "node_thread.h"
27 using namespace fawkes;
55 if (! ros::isInitialized()) {
57 const char *argv[] = {
"fawkes"};
58 ros::init(argc, (
char **)argv,
"fawkes",
59 (uint32_t)ros::init_options::NoSigintHandler);
64 if (ros::isStarted()) {
68 __rosnode =
new ros::NodeHandle();
77 __rosnode->shutdown();
virtual void finalize()
Finalize the thread.
Thread class encapsulation of pthreads.
virtual ~ROSNodeThread()
Destructor.
Logger * logger
This is the Logger member used to access the logger.
Thread aspect to use blocked timing.
void set_rosnode(LockPtr< ros::NodeHandle > rosnode)
Set the ROS node handle to use for aspect initialization.
virtual void loop()
Code to execute in the thread.
virtual void init()
Initialize the thread.
virtual void log_warn(const char *component, const char *format,...)=0
Log warning message.
const char * name() const
Get name of thread.
Thread aspect provide a new aspect.
void clear()
Set underlying instance to 0, decrementing reference count of existing instance appropriately.
ROSNodeThread()
Constructor.