60 ros::NodeHandle&
ros_init(std::string node_name);
67 ros::AsyncSpinner&
ros_spinner(std::string node_name);
ros::AsyncSpinner & ros_spinner(std::string node_name)
ros_spinner return the async_spinner_.
Definition: ros_init.cpp:68
The GlobalRos struct is a structure that allows to gloabally handle the ROS objects.
Definition: ros_init.hh:21
~GlobalRos()
~GlobalRos is a specific destructor that stop the ROS activities
Definition: ros_init.hh:31
void ros_shutdown(std::string node_name)
ros_shutdown shuts down ros and stop the ros spinner with the associate name
Definition: ros_init.cpp:79
bool ros_exist(std::string node_name)
Check if a node handle has been created or not.
Definition: ros_init.cpp:96
boost::shared_ptr< ros::AsyncSpinner > async_spinner_
ros_async_spinner_ is a ros object that handles in a global way all the ros callbacks and interruptio...
Definition: ros_init.hh:51
this is this package namespace in order to avoid naming conflict
Definition: device.hh:22
boost::shared_ptr< ros::NodeHandle > node_handle_
nodeHandle_ is the global node handle used by all ROS objects
Definition: ros_init.hh:45
ros::NodeHandle & ros_init(std::string node_name)
rosInit is a global method that uses the structure GlobalRos.
Definition: ros_init.cpp:31