39 #include <nodelet/NodeletLoad.h> 40 #include <nodelet/NodeletList.h> 41 #include <nodelet/NodeletUnload.h> 43 #include <boost/ptr_container/ptr_map.hpp> 44 #include <boost/utility.hpp> 90 nodelet::NodeletLoad::Response &res)
92 boost::mutex::scoped_lock lock(
lock_);
96 if (req.remap_source_args.size() != req.remap_target_args.size())
98 ROS_ERROR(
"Bad remapppings provided, target and source of different length");
102 for (
size_t i = 0; i < req.remap_source_args.size(); ++i)
109 res.success =
parent_->
load(req.name, req.type, remappings, req.my_argv);
112 if (res.success && !req.bond_id.empty())
124 nodelet::NodeletUnload::Response &res)
126 res.success =
unload(req.name);
132 boost::mutex::scoped_lock lock(
lock_);
137 ROS_ERROR(
"Failed to find nodelet with name '%s' to unload.", name.c_str());
142 M_stringToBond::iterator it =
bond_map_.find(name);
145 it->second->setBrokenCallback(boost::function<
void(
void)>());
154 nodelet::NodeletList::Response &res)
184 : st_queue(new detail::CallbackQueue(cqm, nodelet))
185 , mt_queue(new detail::CallbackQueue(cqm, nodelet))
187 , callback_manager(cqm)
191 callback_manager->
addQueue(st_queue,
false);
192 callback_manager->
addQueue(mt_queue,
true);
206 boost::function<boost::shared_ptr<Nodelet> (
const std::string& lookup_name)> create_instance_;
219 create_instance_ = boost::bind(&Loader::createInstance, loader, _1);
220 refresh_classes_ = boost::bind(&Loader::refreshDeclaredClasses, loader);
224 : create_instance_(create_instance)
230 int num_threads_param;
231 server_nh.
param(
"num_worker_threads", num_threads_param, 0);
233 ROS_INFO(
"Initializing nodelet with %d worker threads.", (
int)callback_manager_->getNumWorkerThreads());
235 services_.reset(
new LoaderROS(parent, server_nh));
252 impl_->advertiseRosApi(
this, server_nh);
266 const std::vector<std::string> & my_argv)
268 boost::mutex::scoped_lock lock(
lock_);
269 if (
impl_->nodelets_.count(name) > 0)
271 ROS_ERROR(
"Cannot load nodelet %s for one exists with that name already", name.c_str());
278 p =
impl_->create_instance_(type);
280 catch (std::runtime_error& e)
283 if(!
impl_->refresh_classes_)
285 ROS_ERROR(
"Failed to load nodelet [%s] of type [%s]: %s", name.c_str(), type.c_str(), e.what());
292 impl_->refresh_classes_();
293 p =
impl_->create_instance_(type);
295 catch (std::runtime_error& e2)
300 ROS_ERROR(
"Failed to load nodelet [%s] of type [%s] even after refreshing the cache: %s", name.c_str(), type.c_str(), e2.what());
301 ROS_ERROR(
"The error before refreshing the cache was: %s", e.what());
310 ROS_DEBUG(
"Done loading nodelet %s", name.c_str());
313 impl_->nodelets_.insert(const_cast<std::string&>(name), mn);
315 mn->st_queue->disable();
316 mn->mt_queue->disable();
318 p->init(name, remappings, my_argv, mn->st_queue.get(), mn->mt_queue.get());
320 mn->st_queue->enable();
321 mn->mt_queue->enable();
324 ROS_DEBUG(
"Done initing nodelet %s", name.c_str());
326 Impl::M_stringToNodelet::iterator it =
impl_->nodelets_.find(name);
327 if (it !=
impl_->nodelets_.end())
329 impl_->nodelets_.erase(it);
330 ROS_DEBUG (
"Failed to initialize nodelet %s", name.c_str ());
339 boost::mutex::scoped_lock lock (
lock_);
340 Impl::M_stringToNodelet::iterator it =
impl_->nodelets_.find(name);
341 if (it !=
impl_->nodelets_.end())
343 impl_->nodelets_.erase(it);
344 ROS_DEBUG (
"Done unloading nodelet %s", name.c_str ());
353 boost::mutex::scoped_lock lock(
lock_);
354 impl_->nodelets_.clear();
360 boost::mutex::scoped_lock lock (
lock_);
361 std::vector<std::string> output;
362 Impl::M_stringToNodelet::iterator it =
impl_->nodelets_.begin();
363 for (; it !=
impl_->nodelets_.end(); ++it)
365 output.push_back(it->first);
bool clear()
Clear all nodelets from this loader.
detail::CallbackQueueManager * callback_manager
void setBrokenCallback(boost::function< void(void)> on_broken)
bool serviceList(nodelet::NodeletList::Request &, nodelet::NodeletList::Response &res)
LoaderROS(Loader *parent, const ros::NodeHandle &nh)
void setCallbackQueue(ros::CallbackQueueInterface *queue)
void removeQueue(const CallbackQueuePtr &queue)
bool load(const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv)
Load a nodelet.
boost::mutex lock_
! Public methods must lock this to preserve internal integrity.
detail::CallbackQueuePtr st_queue
Loader(bool provide_ros_api=true)
Construct the nodelet loader with optional ros API at default location of NodeHandle("~") ...
std::vector< std::string > listLoadedNodelets()
List the names of all loaded nodelets.
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
boost::shared_ptr< LoaderROS > services_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool unload(const std::string &name)
boost::shared_ptr< Nodelet > NodeletPtr
M_stringToNodelet nodelets_
! A map of name to currently constructed nodelets
ros::AsyncSpinner bond_spinner_
Impl(const boost::function< boost::shared_ptr< Nodelet >(const std::string &lookup_name)> &create_instance)
bool unload(const std::string &name)
Unload a nodelet.
boost::scoped_ptr< Impl > impl_
void addQueue(const CallbackQueuePtr &queue, bool threaded)
std::map< std::string, std::string > M_string
boost::function< void()> refresh_classes_
ros::ServiceServer list_server_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::CallbackQueue bond_callback_queue_
const std::string & getNamespace() const
ros::ServiceServer load_server_
ManagedNodelet(const NodeletPtr &nodelet, detail::CallbackQueueManager *cqm)
bool serviceLoad(nodelet::NodeletLoad::Request &req, nodelet::NodeletLoad::Response &res)
ros::ServiceServer unload_server_
A class which will construct and sequentially call Nodelets according to xml This is the primary way ...
void advertiseRosApi(Loader *parent, const ros::NodeHandle &server_nh)
boost::shared_ptr< detail::CallbackQueueManager > callback_manager_
boost::ptr_map< std::string, bond::Bond > M_stringToBond
detail::CallbackQueuePtr mt_queue
bool serviceUnload(nodelet::NodeletUnload::Request &req, nodelet::NodeletUnload::Response &res)
std::map< std::string, std::string > M_string
boost::ptr_map< std::string, ManagedNodelet > M_stringToNodelet