23 #include "node_thread.h" 25 #include <utils/system/hostinfo.h> 57 cfg_async_spinning_ =
false;
62 cfg_async_num_threads_ = 4;
64 cfg_async_num_threads_ =
config->
get_uint(
"/ros/async-num-threads");
67 if (! ros::isInitialized()) {
69 const char *argv[] = {
"fawkes"};
70 std::string node_name =
"fawkes";
74 if (node_name ==
"$HOSTNAME") {
79 ros::init(argc, (
char **)argv, node_name,
80 (uint32_t)ros::init_options::NoSigintHandler);
85 if (ros::isStarted()) {
89 rosnode_ =
new ros::NodeHandle();
93 if (cfg_async_spinning_) {
94 async_spinner_ =
new ros::AsyncSpinner(cfg_async_num_threads_);
95 async_spinner_->start();
103 if (cfg_async_spinning_) {
104 async_spinner_->stop();
105 delete async_spinner_;
107 rosnode_->shutdown();
117 if (! cfg_async_spinning_) {
const char * short_name()
Get short hostname (up to first dot).
virtual void finalize()
Finalize the thread.
Fawkes library namespace.
virtual bool get_bool(const char *path)=0
Get value from configuration which is of type bool.
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.
Base class for exceptions in Fawkes.
const char * name() const
Get name of thread.
virtual void log_warn(const char *component, const char *format,...)=0
Log warning message.
Thread aspect provide a new aspect.
void clear()
Set underlying instance to 0, decrementing reference count of existing instance appropriately.
ROSNodeThread()
Constructor.
virtual unsigned int get_uint(const char *path)=0
Get value from configuration which is of type unsigned int.
Configuration * config
This is the Configuration member used to access the configuration.
virtual std::string get_string(const char *path)=0
Get value from configuration which is of type string.