00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <nodelet/nodelet.h>
00031 #include <nodelet/detail/callback_queue.h>
00032 #include <nodelet/detail/callback_queue_manager.h>
00033
00034 #include <ros/ros.h>
00035 #include <ros/callback_queue.h>
00036
00037
00038
00039
00040 namespace nodelet
00041 {
00042
00044 std::string parentNamespace(const std::string& name)
00045 {
00046 std::string error;
00047 if (!ros::names::validate(name, error))
00048 {
00049 throw ros::InvalidNameException(error);
00050 }
00051
00052 if (!name.compare("")) return "";
00053 if (!name.compare("/")) return "/";
00054
00055 std::string stripped_name;
00056
00057
00058 if (name.find_last_of('/') == name.size()-1)
00059 stripped_name = name.substr(0, name.size() -2);
00060 else
00061 stripped_name = name;
00062
00063
00064 size_t last_pos = stripped_name.find_last_of('/');
00065 if (last_pos == std::string::npos)
00066 {
00067 return "";
00068 }
00069 else if (last_pos == 0)
00070 return "/";
00071 return stripped_name.substr(0, last_pos);
00072 }
00074
00075
00076 Nodelet::Nodelet ()
00077 : inited_(false)
00078 , nodelet_name_("uninitialized")
00079 {
00080 }
00081
00082 Nodelet::~Nodelet ()
00083 {
00084
00085
00086 bond_.reset();
00087
00088 if (inited_)
00089 {
00090 callback_manager_->removeQueue(st_callback_queue_);
00091 callback_manager_->removeQueue(mt_callback_queue_);
00092 }
00093 }
00094
00095 ros::CallbackQueueInterface& Nodelet::getSTCallbackQueue () const
00096 {
00097 if (!inited_)
00098 {
00099 throw UninitializedException("getSTCallbackQueue");
00100 }
00101
00102 return *st_callback_queue_;
00103 }
00104
00105 ros::CallbackQueueInterface& Nodelet::getMTCallbackQueue () const
00106 {
00107 if (!inited_)
00108 {
00109 throw UninitializedException("getMTCallbackQueue");
00110 }
00111
00112 return *mt_callback_queue_;
00113 }
00114
00115 ros::NodeHandle& Nodelet::getNodeHandle() const
00116 {
00117 if (!inited_)
00118 {
00119 throw UninitializedException("getNodeHandle");
00120 }
00121
00122 return *nh_;
00123 }
00124 ros::NodeHandle& Nodelet::getPrivateNodeHandle() const
00125 {
00126 if (!inited_)
00127 {
00128 throw UninitializedException("getPrivateNodeHandle");
00129 }
00130
00131 return *private_nh_;
00132 }
00133 ros::NodeHandle& Nodelet::getMTNodeHandle() const
00134 {
00135 if (!inited_)
00136 {
00137 throw UninitializedException("getMTNodeHandle");
00138 }
00139
00140 return *mt_nh_;
00141 }
00142 ros::NodeHandle& Nodelet::getMTPrivateNodeHandle() const
00143 {
00144 if (!inited_)
00145 {
00146 throw UninitializedException("getMTPrivateNodeHandle");
00147 }
00148
00149 return *mt_private_nh_;
00150 }
00151
00152 void Nodelet::init(const std::string& name, const M_string& remapping_args, const V_string& my_argv, detail::CallbackQueueManager* callback_manager, boost::shared_ptr<bond::Bond> bond)
00153 {
00154 if (inited_)
00155 {
00156 throw MultipleInitializationException();
00157 }
00158
00159 bond_ = bond;
00160
00161 callback_manager_ = callback_manager;
00162 st_callback_queue_.reset(new detail::CallbackQueue(callback_manager));
00163 mt_callback_queue_.reset(new detail::CallbackQueue(callback_manager));
00164
00165 callback_manager->addQueue(st_callback_queue_, false);
00166 callback_manager->addQueue(mt_callback_queue_, true);
00167
00168 nodelet_name_ = name;
00169 my_argv_ = my_argv;
00170
00171 private_nh_.reset(new ros::NodeHandle (name, remapping_args));
00172 private_nh_->setCallbackQueue(st_callback_queue_.get());
00173 nh_.reset(new ros::NodeHandle (parentNamespace(name), remapping_args));
00174 nh_->setCallbackQueue(st_callback_queue_.get());
00175
00176 mt_nh_.reset(new ros::NodeHandle (parentNamespace(name), remapping_args));
00177 mt_nh_->setCallbackQueue(mt_callback_queue_.get());
00178 mt_private_nh_.reset(new ros::NodeHandle (name, remapping_args));
00179 mt_private_nh_->setCallbackQueue(mt_callback_queue_.get());
00180
00181 NODELET_DEBUG ("Nodelet initializing");
00182 inited_ = true;
00183 this->onInit ();
00184 }
00185
00186 }