42 , nodelet_name_(
"uninitialized")
57 return *
nh_->getCallbackQueue();
67 return *
mt_nh_->getCallbackQueue();
128 nh_->setCallbackQueue(st_queue);
130 mt_nh_->setCallbackQueue(mt_queue);
ROSCPP_DECL std::string parentNamespace(const std::string &name)
NodeHandlePtr private_nh_
ros::NodeHandle & getMTNodeHandle() const
ros::CallbackQueueInterface & getMTCallbackQueue() const
void init(const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
Init function called at startup.
ros::NodeHandle & getPrivateNodeHandle() const
std::string nodelet_name_
ros::NodeHandle & getMTPrivateNodeHandle() const
ros::CallbackQueueInterface & getSTCallbackQueue() const
Nodelet()
Empty constructor required for dynamic loading.
ros::NodeHandle & getNodeHandle() const
#define NODELET_DEBUG(...)
std::vector< std::string > V_string
std::map< std::string, std::string > M_string
NodeHandlePtr mt_private_nh_