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/loader.h>
00031 #include <nodelet/nodelet.h>
00032 #include <nodelet/detail/callback_queue_manager.h>
00033 #include <pluginlib/class_loader.h>
00034
00035 #include <ros/ros.h>
00036 #include <nodelet/NodeletLoad.h>
00037 #include <nodelet/NodeletList.h>
00038 #include <nodelet/NodeletUnload.h>
00039
00040 #include <sstream>
00041 #include <map>
00042 #include <boost/shared_ptr.hpp>
00043
00044 namespace nodelet
00045 {
00046
00047 namespace detail
00048 {
00049 class LoaderROS
00050 {
00051 public:
00052 LoaderROS(Loader* parent, const ros::NodeHandle& nh)
00053 : parent_(parent)
00054 , nh_(nh)
00055 {
00056 load_server_ = nh_.advertiseService("load_nodelet", &LoaderROS::serviceLoad, this);
00057 unload_server_ = nh_.advertiseService("unload_nodelet", &LoaderROS::serviceUnload, this);
00058 list_server_ = nh_.advertiseService("list", &LoaderROS::serviceList, this);
00059 }
00060
00061 private:
00062 bool serviceLoad(nodelet::NodeletLoad::Request &req,
00063 nodelet::NodeletLoad::Response &res)
00064 {
00065
00066 M_string remappings;
00067 if (req.remap_source_args.size() != req.remap_target_args.size())
00068 {
00069 ROS_ERROR("Bad remapppings provided, target and source of different length");
00070 }
00071 else
00072 {
00073
00074 for (size_t i = 0; i < req.remap_source_args.size(); ++i)
00075 {
00076
00077 remappings[ros::names::resolve(req.remap_source_args[i])] = ros::names::resolve(req.remap_target_args[i]);
00078 ROS_DEBUG("%s:%s\n", ros::names::resolve(req.remap_source_args[i]).c_str(), remappings[ros::names::resolve(req.remap_source_args[i])].c_str());
00079 }
00080 }
00081
00082 boost::shared_ptr<bond::Bond> bond;
00083 if (!req.bond_id.empty())
00084 {
00085 bond.reset(new bond::Bond(nh_.getNamespace() + "/bond", req.bond_id));
00086 }
00087
00088 res.success = parent_->load(req.name, req.type, remappings, req.my_argv, bond);
00089 if (bond)
00090 bond->start();
00091 return res.success;
00092 }
00093
00094 bool serviceUnload(nodelet::NodeletUnload::Request &req,
00095 nodelet::NodeletUnload::Response &res)
00096 {
00097 res.success = parent_->unload(req.name);
00098 if (!res.success)
00099 {
00100 ROS_ERROR("Failed to find nodelet with name '%s' to unload.", req.name.c_str());
00101 }
00102
00103 return res.success;
00104 }
00105
00106 bool serviceList(nodelet::NodeletList::Request &req,
00107 nodelet::NodeletList::Response &res)
00108 {
00109
00110 res.nodelets = parent_->listLoadedNodelets();
00111 return true;
00112 }
00113
00114 Loader* parent_;
00115 ros::NodeHandle nh_;
00116 ros::ServiceServer load_server_;
00117 ros::ServiceServer unload_server_;
00118 ros::ServiceServer list_server_;
00119 };
00120 }
00121
00122 Loader::Loader(bool provide_ros_api)
00123 : loader_(new pluginlib::ClassLoader<Nodelet>("nodelet", "nodelet::Nodelet"))
00124 {
00125 constructorImplementation(provide_ros_api, ros::NodeHandle("~"));
00126 }
00127
00128 Loader::Loader(ros::NodeHandle server_nh)
00129 : loader_(new pluginlib::ClassLoader<Nodelet>("nodelet", "nodelet::Nodelet"))
00130 {
00131 constructorImplementation(true, server_nh);
00132 }
00133
00134 void Loader::constructorImplementation(bool provide_ros_api, ros::NodeHandle server_nh)
00135 {
00136 std::string lib_string = "";
00137 std::vector<std::string> libs = loader_->getDeclaredClasses();
00138 for (size_t i = 0 ; i < libs.size(); ++i)
00139 {
00140 lib_string = lib_string + std::string(", ") + libs[i];
00141 }
00142
00143 if (provide_ros_api)
00144 {
00145 services_.reset(new detail::LoaderROS(this, server_nh));
00146 ROS_DEBUG("In nodelet::Loader found the following libs: %s", lib_string.c_str());
00147 int num_threads_param;
00148 if (server_nh.getParam ("num_worker_threads", num_threads_param))
00149 {
00150 callback_manager_ = detail::CallbackQueueManagerPtr (new detail::CallbackQueueManager (num_threads_param));
00151 ROS_INFO("Initializing nodelet with %d worker threads.", num_threads_param);
00152 }
00153 }
00154 if (!callback_manager_)
00155 callback_manager_ = detail::CallbackQueueManagerPtr (new detail::CallbackQueueManager);
00156 }
00157
00158 Loader::~Loader()
00159 {
00160 clear();
00161
00162 }
00163
00164 bool Loader::load(const std::string &name, const std::string& type, const ros::M_string& remappings, const std::vector<std::string> & my_argv, boost::shared_ptr<bond::Bond> bond)
00165 {
00166 boost::mutex::scoped_lock lock (lock_);
00167 if (nodelets_.count(name) > 0)
00168 {
00169 ROS_ERROR("Cannot load nodelet %s for one exists with that name already", name.c_str());
00170 return false;
00171 }
00172
00173
00174 try
00175 {
00176 NodeletPtr p(loader_->createClassInstance(type));
00177 if (!p)
00178 {
00179 return false;
00180 }
00181
00182 nodelets_[name] = p;
00183 ROS_DEBUG("Done loading nodelet %s", name.c_str());
00184
00185 p->init(name, remappings, my_argv, callback_manager_.get(), bond);
00186
00187 if (bond)
00188 bond->setBrokenCallback(boost::bind(&Loader::unload, this, name));
00189
00190 ROS_DEBUG("Done initing nodelet %s", name.c_str());
00191 return true;
00192 }
00193 catch (pluginlib::PluginlibException& e)
00194 {
00195 ROS_ERROR("Failed to load nodelet [%s] of type [%s]: %s", name.c_str(), type.c_str(), e.what());
00196 }
00197
00198 return false;
00199 }
00200
00201 bool Loader::unload (const std::string & name)
00202 {
00203 boost::mutex::scoped_lock lock (lock_);
00204 M_stringToNodelet::iterator it = nodelets_.find (name);
00205 if (it != nodelets_.end ())
00206 {
00207 nodelets_.erase (it);
00208 ROS_DEBUG ("Done unloading nodelet %s", name.c_str ());
00209 return (true);
00210 }
00211
00212 return (false);
00213 }
00214
00216 bool Loader::clear ()
00217 {
00218 boost::mutex::scoped_lock lock (lock_);
00219 nodelets_.clear ();
00220 return (true);
00221 };
00222
00224 std::vector<std::string> Loader::listLoadedNodelets()
00225 {
00226 boost::mutex::scoped_lock lock (lock_);
00227 std::vector<std::string> output;
00228 std::map< std::string, boost::shared_ptr<Nodelet> >::iterator it = nodelets_.begin();
00229 for (; it != nodelets_.end(); ++it)
00230 {
00231 output.push_back(it->first);
00232 }
00233 return output;
00234 }
00235
00236 }
00237