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 namespace nodelet
00038 {
00039
00040 Nodelet::Nodelet ()
00041 : inited_(false)
00042 , nodelet_name_("uninitialized")
00043 {
00044 }
00045
00046 Nodelet::~Nodelet ()
00047 {
00048 bond_.reset();
00049 }
00050
00051 void Nodelet::disable()
00052 {
00053 st_callback_queue_->disable();
00054 mt_callback_queue_->disable();
00055 }
00056
00057 ros::CallbackQueueInterface& Nodelet::getSTCallbackQueue () const
00058 {
00059 if (!inited_)
00060 {
00061 throw UninitializedException("getSTCallbackQueue");
00062 }
00063
00064 return *st_callback_queue_;
00065 }
00066
00067 ros::CallbackQueueInterface& Nodelet::getMTCallbackQueue () const
00068 {
00069 if (!inited_)
00070 {
00071 throw UninitializedException("getMTCallbackQueue");
00072 }
00073
00074 return *mt_callback_queue_;
00075 }
00076
00077 ros::NodeHandle& Nodelet::getNodeHandle() const
00078 {
00079 if (!inited_)
00080 {
00081 throw UninitializedException("getNodeHandle");
00082 }
00083
00084 return *nh_;
00085 }
00086 ros::NodeHandle& Nodelet::getPrivateNodeHandle() const
00087 {
00088 if (!inited_)
00089 {
00090 throw UninitializedException("getPrivateNodeHandle");
00091 }
00092
00093 return *private_nh_;
00094 }
00095 ros::NodeHandle& Nodelet::getMTNodeHandle() const
00096 {
00097 if (!inited_)
00098 {
00099 throw UninitializedException("getMTNodeHandle");
00100 }
00101
00102 return *mt_nh_;
00103 }
00104 ros::NodeHandle& Nodelet::getMTPrivateNodeHandle() const
00105 {
00106 if (!inited_)
00107 {
00108 throw UninitializedException("getMTPrivateNodeHandle");
00109 }
00110
00111 return *mt_private_nh_;
00112 }
00113
00114 void Nodelet::init(const std::string& name, const M_string& remapping_args, const V_string& my_argv,
00115 detail::CallbackQueueManager* callback_manager, boost::shared_ptr<bond::Bond> bond)
00116 {
00117 if (inited_)
00118 {
00119 throw MultipleInitializationException();
00120 }
00121
00122 bond_ = bond;
00123
00124 callback_manager_ = callback_manager;
00125
00126
00127
00128
00130 callback_manager->addQueue(st_callback_queue_, false);
00131 callback_manager->addQueue(mt_callback_queue_, true);
00132
00133 nodelet_name_ = name;
00134 my_argv_ = my_argv;
00135
00136 private_nh_.reset(new ros::NodeHandle(name, remapping_args));
00137 private_nh_->setCallbackQueue(st_callback_queue_.get());
00138 nh_.reset(new ros::NodeHandle(ros::names::parentNamespace(name), remapping_args));
00139 nh_->setCallbackQueue(st_callback_queue_.get());
00140
00141 mt_nh_.reset(new ros::NodeHandle(ros::names::parentNamespace(name), remapping_args));
00142 mt_nh_->setCallbackQueue(mt_callback_queue_.get());
00143 mt_private_nh_.reset(new ros::NodeHandle (name, remapping_args));
00144 mt_private_nh_->setCallbackQueue(mt_callback_queue_.get());
00145
00146 NODELET_DEBUG ("Nodelet initializing");
00147 inited_ = true;
00148 this->onInit ();
00149 }
00150
00151 }