From 11d11241e62f98259396e858e48a45e6874c10f4 Mon Sep 17 00:00:00 2001 From: Kentaro Wada Date: Thu, 12 Nov 2015 04:23:13 +0900 Subject: [PATCH] [nodelet] Public api to check nodelet is initialized --- nodelet/include/nodelet/nodelet.h | 3 +++ nodelet/src/nodelet_class.cpp | 7 ++++++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/nodelet/include/nodelet/nodelet.h b/nodelet/include/nodelet/nodelet.h index 5e330110..07714699 100644 --- a/nodelet/include/nodelet/nodelet.h +++ b/nodelet/include/nodelet/nodelet.h @@ -218,6 +218,9 @@ class Nodelet /**\brief Empty constructor required for dynamic loading */ Nodelet(); + /**\brief Whether the nodelet is initialized */ + bool is_initialized(); + /**\brief Init function called at startup * \param name The name of the nodelet * \param remapping_args The remapping args in a map for the nodelet diff --git a/nodelet/src/nodelet_class.cpp b/nodelet/src/nodelet_class.cpp index 088e856b..b64a906c 100644 --- a/nodelet/src/nodelet_class.cpp +++ b/nodelet/src/nodelet_class.cpp @@ -104,6 +104,11 @@ ros::NodeHandle& Nodelet::getMTPrivateNodeHandle() const return *mt_private_nh_; } +bool Nodelet::is_initialized() +{ + return inited_; +} + void Nodelet::init(const std::string& name, const M_string& remapping_args, const V_string& my_argv, ros::CallbackQueueInterface* st_queue, ros::CallbackQueueInterface* mt_queue) { @@ -129,8 +134,8 @@ void Nodelet::init(const std::string& name, const M_string& remapping_args, cons mt_nh_->setCallbackQueue(mt_queue); NODELET_DEBUG ("Nodelet initializing"); - inited_ = true; this->onInit (); + inited_ = true; } } // namespace nodelet