Fawkes API
Fawkes Development Version
|
23 #include "node_thread.h"
26 #include <utils/system/hostinfo.h>
54 cfg_async_spinning_ =
false;
60 cfg_async_num_threads_ = 4;
62 cfg_async_num_threads_ =
config->
get_uint(
"/ros/async-num-threads");
66 if (!ros::isInitialized()) {
68 const char *argv[] = {
"fawkes"};
69 std::string node_name =
"fawkes";
74 if (node_name ==
"$HOSTNAME") {
79 ros::init(argc, (
char **)argv, node_name, (uint32_t)ros::init_options::NoSigintHandler);
84 if (ros::isStarted()) {
88 rosnode_ =
new ros::NodeHandle();
92 if (cfg_async_spinning_) {
93 async_spinner_ =
new ros::AsyncSpinner(cfg_async_num_threads_);
94 async_spinner_->start();
101 if (cfg_async_spinning_) {
102 async_spinner_->stop();
103 delete async_spinner_;
105 rosnode_->shutdown();
114 if (!cfg_async_spinning_) {
virtual ~ROSNodeThread()
Destructor.
ROSNodeThread()
Constructor.
virtual bool get_bool(const char *path)=0
void set_rosnode(LockPtr< ros::NodeHandle > rosnode)
Set the ROS node handle to use for aspect initialization.
const char * name() const
const char * short_name()
Get short hostname (up to first dot).
void clear()
Set underlying instance to 0, decrementing reference count of existing instance appropriately.
virtual void init()
Initialize the thread.
virtual void log_warn(const char *component, const char *format,...)=0
virtual unsigned int get_uint(const char *path)=0
virtual std::string get_string(const char *path)=0
virtual void finalize()
Finalize the thread.
virtual void loop()
Code to execute in the thread.