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 #include "ros/node_handle.h"
00029 #include "ros/this_node.h"
00030 #include "ros/service.h"
00031 #include "ros/callback_queue.h"
00032 #include "ros/timer_manager.h"
00033
00034 #include "ros/time.h"
00035 #include "ros/rate.h"
00036
00037 #include "ros/xmlrpc_manager.h"
00038 #include "ros/topic_manager.h"
00039 #include "ros/service_manager.h"
00040 #include "ros/master.h"
00041 #include "ros/param.h"
00042 #include "ros/names.h"
00043 #include "ros/init.h"
00044 #include "ros/this_node.h"
00045 #include "XmlRpc.h"
00046
00047 #include <boost/thread.hpp>
00048
00049 namespace ros
00050 {
00051
00052 boost::mutex g_nh_refcount_mutex;
00053 int32_t g_nh_refcount = 0;
00054 bool g_node_started_by_nh = false;
00055
00056 class NodeHandleBackingCollection
00057 {
00058 public:
00059 typedef std::vector<Publisher::ImplWPtr> V_PubImpl;
00060 typedef std::vector<ServiceServer::ImplWPtr> V_SrvImpl;
00061 typedef std::vector<Subscriber::ImplWPtr> V_SubImpl;
00062 typedef std::vector<ServiceClient::ImplWPtr> V_SrvCImpl;
00063 V_PubImpl pubs_;
00064 V_SrvImpl srvs_;
00065 V_SubImpl subs_;
00066 V_SrvCImpl srv_cs_;
00067
00068 boost::mutex mutex_;
00069 };
00070
00071 NodeHandle::NodeHandle(const std::string& ns, const M_string& remappings)
00072 : namespace_(this_node::getNamespace())
00073 , callback_queue_(0)
00074 , collection_(0)
00075 {
00076 std::string tilde_resolved_ns;
00077 if (!ns.empty() && ns[0] == '~')
00078 tilde_resolved_ns = names::resolve(ns);
00079 else
00080 tilde_resolved_ns = ns;
00081
00082 construct(tilde_resolved_ns, true);
00083
00084 initRemappings(remappings);
00085 }
00086
00087 NodeHandle::NodeHandle(const NodeHandle& parent, const std::string& ns)
00088 : collection_(0)
00089 {
00090 namespace_ = parent.getNamespace();
00091 callback_queue_ = parent.callback_queue_;
00092
00093 remappings_ = parent.remappings_;
00094 unresolved_remappings_ = parent.unresolved_remappings_;
00095
00096 construct(ns, false);
00097 }
00098
00099 NodeHandle::NodeHandle(const NodeHandle& parent, const std::string& ns, const M_string& remappings)
00100 : collection_(0)
00101 {
00102 namespace_ = parent.getNamespace();
00103 callback_queue_ = parent.callback_queue_;
00104
00105 remappings_ = parent.remappings_;
00106 unresolved_remappings_ = parent.unresolved_remappings_;
00107
00108 construct(ns, false);
00109
00110 initRemappings(remappings);
00111 }
00112
00113 NodeHandle::NodeHandle(const NodeHandle& rhs)
00114 : collection_(0)
00115 {
00116 callback_queue_ = rhs.callback_queue_;
00117 remappings_ = rhs.remappings_;
00118 unresolved_remappings_ = rhs.unresolved_remappings_;
00119
00120 construct(rhs.namespace_, true);
00121
00122 unresolved_namespace_ = rhs.unresolved_namespace_;
00123 }
00124
00125 NodeHandle::~NodeHandle()
00126 {
00127 destruct();
00128 }
00129
00130 NodeHandle& NodeHandle::operator=(const NodeHandle& rhs)
00131 {
00132 ROS_ASSERT(collection_);
00133 namespace_ = rhs.namespace_;
00134 callback_queue_ = rhs.callback_queue_;
00135 remappings_ = rhs.remappings_;
00136 unresolved_remappings_ = rhs.unresolved_remappings_;
00137
00138 return *this;
00139 }
00140
00141 void spinThread()
00142 {
00143 ros::spin();
00144 }
00145
00146 void NodeHandle::construct(const std::string& ns, bool validate_name)
00147 {
00148 if (!ros::isInitialized())
00149 {
00150 ROS_FATAL("You must call ros::init() before creating the first NodeHandle");
00151 ROS_BREAK();
00152 }
00153
00154 collection_ = new NodeHandleBackingCollection;
00155 unresolved_namespace_ = ns;
00156
00157
00158 if (validate_name)
00159 namespace_ = resolveName(ns, true);
00160 else
00161 {
00162 namespace_ = resolveName(ns, true, no_validate());
00163
00164 }
00165 ok_ = true;
00166
00167 boost::mutex::scoped_lock lock(g_nh_refcount_mutex);
00168
00169 if (g_nh_refcount == 0 && !ros::isStarted())
00170 {
00171 g_node_started_by_nh = true;
00172 ros::start();
00173 }
00174
00175 ++g_nh_refcount;
00176 }
00177
00178 void NodeHandle::destruct()
00179 {
00180 delete collection_;
00181
00182 boost::mutex::scoped_lock lock(g_nh_refcount_mutex);
00183
00184 --g_nh_refcount;
00185
00186 if (g_nh_refcount == 0 && g_node_started_by_nh)
00187 {
00188 ros::shutdown();
00189 }
00190 }
00191
00192 void NodeHandle::initRemappings(const M_string& remappings)
00193 {
00194 {
00195 M_string::const_iterator it = remappings.begin();
00196 M_string::const_iterator end = remappings.end();
00197 for (; it != end; ++it)
00198 {
00199 const std::string& from = it->first;
00200 const std::string& to = it->second;
00201
00202 remappings_.insert(std::make_pair(resolveName(from, false), resolveName(to, false)));
00203 unresolved_remappings_.insert(std::make_pair(from, to));
00204 }
00205 }
00206 }
00207
00208 void NodeHandle::setCallbackQueue(CallbackQueueInterface* queue)
00209 {
00210 callback_queue_ = queue;
00211 }
00212
00213 std::string NodeHandle::remapName(const std::string& name) const
00214 {
00215 std::string resolved = resolveName(name, false);
00216
00217
00218 M_string::const_iterator it = remappings_.find(resolved);
00219 if (it != remappings_.end())
00220 {
00221
00222 return it->second;
00223 }
00224
00225
00226 return names::remap(resolved);
00227 }
00228
00229 std::string NodeHandle::resolveName(const std::string& name, bool remap) const
00230 {
00231
00232 std::string error;
00233 if (!names::validate(name, error))
00234 {
00235 throw InvalidNameException(error);
00236 }
00237
00238 return resolveName(name, remap, no_validate());
00239 }
00240
00241 std::string NodeHandle::resolveName(const std::string& name, bool remap, no_validate) const
00242 {
00243 if (name.empty())
00244 {
00245 return namespace_;
00246 }
00247
00248 std::string final = name;
00249
00250 if (final[0] == '~')
00251 {
00252 std::stringstream ss;
00253 ss << "Using ~ names with NodeHandle methods is not allowed. If you want to use private names with the NodeHandle ";
00254 ss << "interface, construct a NodeHandle using a private name as its namespace. e.g. ";
00255 ss << "ros::NodeHandle nh(\"~\"); ";
00256 ss << "nh.getParam(\"my_private_name\");";
00257 ss << " (name = [" << name << "])";
00258 throw InvalidNameException(ss.str());
00259 }
00260 else if (final[0] == '/')
00261 {
00262
00263 }
00264 else if (!namespace_.empty())
00265 {
00266
00267 final = names::append(namespace_, final);
00268 }
00269
00270
00271 final = names::clean(final);
00272
00273
00274 if (remap)
00275 {
00276 final = remapName(final);
00277
00278 }
00279
00280 return names::resolve(final, false);
00281 }
00282
00283 Publisher NodeHandle::advertise(AdvertiseOptions& ops)
00284 {
00285 ops.topic = resolveName(ops.topic);
00286 if (ops.callback_queue == 0)
00287 {
00288 if (callback_queue_)
00289 {
00290 ops.callback_queue = callback_queue_;
00291 }
00292 else
00293 {
00294 ops.callback_queue = getGlobalCallbackQueue();
00295 }
00296 }
00297
00298 SubscriberCallbacksPtr callbacks(boost::make_shared<SubscriberCallbacks>(ops.connect_cb, ops.disconnect_cb,
00299 ops.tracked_object, ops.callback_queue));
00300
00301 if (TopicManager::instance()->advertise(ops, callbacks))
00302 {
00303 Publisher pub(ops.topic, ops.md5sum, ops.datatype, *this, callbacks);
00304
00305 {
00306 boost::mutex::scoped_lock lock(collection_->mutex_);
00307 collection_->pubs_.push_back(pub.impl_);
00308 }
00309
00310 return pub;
00311 }
00312
00313 return Publisher();
00314 }
00315
00316 Subscriber NodeHandle::subscribe(SubscribeOptions& ops)
00317 {
00318 ops.topic = resolveName(ops.topic);
00319 if (ops.callback_queue == 0)
00320 {
00321 if (callback_queue_)
00322 {
00323 ops.callback_queue = callback_queue_;
00324 }
00325 else
00326 {
00327 ops.callback_queue = getGlobalCallbackQueue();
00328 }
00329 }
00330
00331 if (TopicManager::instance()->subscribe(ops))
00332 {
00333 Subscriber sub(ops.topic, *this, ops.helper);
00334
00335 {
00336 boost::mutex::scoped_lock lock(collection_->mutex_);
00337 collection_->subs_.push_back(sub.impl_);
00338 }
00339
00340 return sub;
00341 }
00342
00343 return Subscriber();
00344 }
00345
00346 ServiceServer NodeHandle::advertiseService(AdvertiseServiceOptions& ops)
00347 {
00348 ops.service = resolveName(ops.service);
00349 if (ops.callback_queue == 0)
00350 {
00351 if (callback_queue_)
00352 {
00353 ops.callback_queue = callback_queue_;
00354 }
00355 else
00356 {
00357 ops.callback_queue = getGlobalCallbackQueue();
00358 }
00359 }
00360
00361 if (ServiceManager::instance()->advertiseService(ops))
00362 {
00363 ServiceServer srv(ops.service, *this);
00364
00365 {
00366 boost::mutex::scoped_lock lock(collection_->mutex_);
00367 collection_->srvs_.push_back(srv.impl_);
00368 }
00369
00370 return srv;
00371 }
00372
00373 return ServiceServer();
00374 }
00375
00376 ServiceClient NodeHandle::serviceClient(ServiceClientOptions& ops)
00377 {
00378 ops.service = resolveName(ops.service);
00379 ServiceClient client(ops.service, ops.persistent, ops.header, ops.md5sum);
00380
00381 if (client)
00382 {
00383 boost::mutex::scoped_lock lock(collection_->mutex_);
00384 collection_->srv_cs_.push_back(client.impl_);
00385 }
00386
00387 return client;
00388 }
00389
00390 Timer NodeHandle::createTimer(Duration period, const TimerCallback& callback,
00391 bool oneshot, bool autostart) const
00392 {
00393 TimerOptions ops;
00394 ops.period = period;
00395 ops.callback = callback;
00396 ops.oneshot = oneshot;
00397 ops.autostart = autostart;
00398 return createTimer(ops);
00399 }
00400
00401 Timer NodeHandle::createTimer(TimerOptions& ops) const
00402 {
00403 if (ops.callback_queue == 0)
00404 {
00405 if (callback_queue_)
00406 {
00407 ops.callback_queue = callback_queue_;
00408 }
00409 else
00410 {
00411 ops.callback_queue = getGlobalCallbackQueue();
00412 }
00413 }
00414
00415 Timer timer(ops);
00416 if (ops.autostart)
00417 timer.start();
00418 return timer;
00419 }
00420
00421 WallTimer NodeHandle::createWallTimer(WallDuration period, const WallTimerCallback& callback,
00422 bool oneshot, bool autostart) const
00423 {
00424 WallTimerOptions ops;
00425 ops.period = period;
00426 ops.callback = callback;
00427 ops.oneshot = oneshot;
00428 ops.autostart = autostart;
00429 return createWallTimer(ops);
00430 }
00431
00432 WallTimer NodeHandle::createWallTimer(WallTimerOptions& ops) const
00433 {
00434 if (ops.callback_queue == 0)
00435 {
00436 if (callback_queue_)
00437 {
00438 ops.callback_queue = callback_queue_;
00439 }
00440 else
00441 {
00442 ops.callback_queue = getGlobalCallbackQueue();
00443 }
00444 }
00445
00446 WallTimer timer(ops);
00447 if (ops.autostart)
00448 timer.start();
00449 return timer;
00450 }
00451
00452 void NodeHandle::shutdown()
00453 {
00454 {
00455 NodeHandleBackingCollection::V_SubImpl::iterator it = collection_->subs_.begin();
00456 NodeHandleBackingCollection::V_SubImpl::iterator end = collection_->subs_.end();
00457 for (; it != end; ++it)
00458 {
00459 Subscriber::ImplPtr impl = it->lock();
00460
00461 if (impl)
00462 {
00463 impl->unsubscribe();
00464 }
00465 }
00466 }
00467
00468 {
00469 NodeHandleBackingCollection::V_PubImpl::iterator it = collection_->pubs_.begin();
00470 NodeHandleBackingCollection::V_PubImpl::iterator end = collection_->pubs_.end();
00471 for (; it != end; ++it)
00472 {
00473 Publisher::ImplPtr impl = it->lock();
00474
00475 if (impl)
00476 {
00477 impl->unadvertise();
00478 }
00479 }
00480 }
00481
00482 {
00483 NodeHandleBackingCollection::V_SrvImpl::iterator it = collection_->srvs_.begin();
00484 NodeHandleBackingCollection::V_SrvImpl::iterator end = collection_->srvs_.end();
00485 for (; it != end; ++it)
00486 {
00487 ServiceServer::ImplPtr impl = it->lock();
00488
00489 if (impl)
00490 {
00491 impl->unadvertise();
00492 }
00493 }
00494 }
00495
00496 {
00497 NodeHandleBackingCollection::V_SrvCImpl::iterator it = collection_->srv_cs_.begin();
00498 NodeHandleBackingCollection::V_SrvCImpl::iterator end = collection_->srv_cs_.end();
00499 for (; it != end; ++it)
00500 {
00501 ServiceClient::ImplPtr impl = it->lock();
00502
00503 if (impl)
00504 {
00505 impl->shutdown();
00506 }
00507 }
00508 }
00509
00510 ok_ = false;
00511 }
00512
00513 void NodeHandle::setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const
00514 {
00515 return param::set(resolveName(key), v);
00516 }
00517
00518 void NodeHandle::setParam(const std::string& key, const std::string& s) const
00519 {
00520 return param::set(resolveName(key), s);
00521 }
00522
00523 void NodeHandle::setParam(const std::string& key, const char* s) const
00524 {
00525 return param::set(resolveName(key), s);
00526 }
00527
00528 void NodeHandle::setParam(const std::string& key, double d) const
00529 {
00530 return param::set(resolveName(key), d);
00531 }
00532
00533 void NodeHandle::setParam(const std::string& key, int i) const
00534 {
00535 return param::set(resolveName(key), i);
00536 }
00537
00538 void NodeHandle::setParam(const std::string& key, bool b) const
00539 {
00540 return param::set(resolveName(key), b);
00541 }
00542
00543 void NodeHandle::setParam(const std::string& key, const std::vector<std::string>& vec) const
00544 {
00545 return param::set(resolveName(key), vec);
00546 }
00547 void NodeHandle::setParam(const std::string& key, const std::vector<double>& vec) const
00548 {
00549 return param::set(resolveName(key), vec);
00550 }
00551 void NodeHandle::setParam(const std::string& key, const std::vector<float>& vec) const
00552 {
00553 return param::set(resolveName(key), vec);
00554 }
00555 void NodeHandle::setParam(const std::string& key, const std::vector<int>& vec) const
00556 {
00557 return param::set(resolveName(key), vec);
00558 }
00559 void NodeHandle::setParam(const std::string& key, const std::vector<bool>& vec) const
00560 {
00561 return param::set(resolveName(key), vec);
00562 }
00563
00564 void NodeHandle::setParam(const std::string& key, const std::map<std::string, std::string>& map) const
00565 {
00566 return param::set(resolveName(key), map);
00567 }
00568 void NodeHandle::setParam(const std::string& key, const std::map<std::string, double>& map) const
00569 {
00570 return param::set(resolveName(key), map);
00571 }
00572 void NodeHandle::setParam(const std::string& key, const std::map<std::string, float>& map) const
00573 {
00574 return param::set(resolveName(key), map);
00575 }
00576 void NodeHandle::setParam(const std::string& key, const std::map<std::string, int>& map) const
00577 {
00578 return param::set(resolveName(key), map);
00579 }
00580 void NodeHandle::setParam(const std::string& key, const std::map<std::string, bool>& map) const
00581 {
00582 return param::set(resolveName(key), map);
00583 }
00584
00585 bool NodeHandle::hasParam(const std::string& key) const
00586 {
00587 return param::has(resolveName(key));
00588 }
00589
00590 bool NodeHandle::deleteParam(const std::string& key) const
00591 {
00592 return param::del(resolveName(key));
00593 }
00594
00595 bool NodeHandle::getParamNames(std::vector<std::string>& keys) const
00596 {
00597 return param::getParamNames(keys);
00598 }
00599
00600 bool NodeHandle::getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const
00601 {
00602 return param::get(resolveName(key), v);
00603 }
00604
00605 bool NodeHandle::getParam(const std::string& key, std::string& s) const
00606 {
00607 return param::get(resolveName(key), s);
00608 }
00609
00610 bool NodeHandle::getParam(const std::string& key, double& d) const
00611 {
00612 return param::get(resolveName(key), d);
00613 }
00614
00615 bool NodeHandle::getParam(const std::string& key, float& f) const
00616 {
00617 return param::get(resolveName(key), f);
00618 }
00619
00620 bool NodeHandle::getParam(const std::string& key, int& i) const
00621 {
00622 return param::get(resolveName(key), i);
00623 }
00624
00625 bool NodeHandle::getParam(const std::string& key, bool& b) const
00626 {
00627 return param::get(resolveName(key), b);
00628 }
00629
00630
00631 bool NodeHandle::getParam(const std::string& key, std::vector<std::string>& vec) const
00632 {
00633 return param::get(resolveName(key), vec);
00634 }
00635 bool NodeHandle::getParam(const std::string& key, std::vector<double>& vec) const
00636 {
00637 return param::get(resolveName(key), vec);
00638 }
00639 bool NodeHandle::getParam(const std::string& key, std::vector<float>& vec) const
00640 {
00641 return param::get(resolveName(key), vec);
00642 }
00643 bool NodeHandle::getParam(const std::string& key, std::vector<int>& vec) const
00644 {
00645 return param::get(resolveName(key), vec);
00646 }
00647 bool NodeHandle::getParam(const std::string& key, std::vector<bool>& vec) const
00648 {
00649 return param::get(resolveName(key), vec);
00650 }
00651
00652 bool NodeHandle::getParam(const std::string& key, std::map<std::string, std::string>& map) const
00653 {
00654 return param::get(resolveName(key), map);
00655 }
00656 bool NodeHandle::getParam(const std::string& key, std::map<std::string, double>& map) const
00657 {
00658 return param::get(resolveName(key), map);
00659 }
00660 bool NodeHandle::getParam(const std::string& key, std::map<std::string, float>& map) const
00661 {
00662 return param::get(resolveName(key), map);
00663 }
00664 bool NodeHandle::getParam(const std::string& key, std::map<std::string, int>& map) const
00665 {
00666 return param::get(resolveName(key), map);
00667 }
00668 bool NodeHandle::getParam(const std::string& key, std::map<std::string, bool>& map) const
00669 {
00670 return param::get(resolveName(key), map);
00671 }
00672
00673 bool NodeHandle::getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const
00674 {
00675 return param::getCached(resolveName(key), v);
00676 }
00677
00678 bool NodeHandle::getParamCached(const std::string& key, std::string& s) const
00679 {
00680 return param::getCached(resolveName(key), s);
00681 }
00682
00683 bool NodeHandle::getParamCached(const std::string& key, double& d) const
00684 {
00685 return param::getCached(resolveName(key), d);
00686 }
00687
00688 bool NodeHandle::getParamCached(const std::string& key, float& f) const
00689 {
00690 return param::getCached(resolveName(key), f);
00691 }
00692
00693 bool NodeHandle::getParamCached(const std::string& key, int& i) const
00694 {
00695 return param::getCached(resolveName(key), i);
00696 }
00697
00698 bool NodeHandle::getParamCached(const std::string& key, bool& b) const
00699 {
00700 return param::getCached(resolveName(key), b);
00701 }
00702
00703 bool NodeHandle::getParamCached(const std::string& key, std::vector<std::string>& vec) const
00704 {
00705 return param::getCached(resolveName(key), vec);
00706 }
00707 bool NodeHandle::getParamCached(const std::string& key, std::vector<double>& vec) const
00708 {
00709 return param::getCached(resolveName(key), vec);
00710 }
00711 bool NodeHandle::getParamCached(const std::string& key, std::vector<float>& vec) const
00712 {
00713 return param::getCached(resolveName(key), vec);
00714 }
00715 bool NodeHandle::getParamCached(const std::string& key, std::vector<int>& vec) const
00716 {
00717 return param::getCached(resolveName(key), vec);
00718 }
00719 bool NodeHandle::getParamCached(const std::string& key, std::vector<bool>& vec) const
00720 {
00721 return param::getCached(resolveName(key), vec);
00722 }
00723
00724 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, std::string>& map) const
00725 {
00726 return param::getCached(resolveName(key), map);
00727 }
00728 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, double>& map) const
00729 {
00730 return param::getCached(resolveName(key), map);
00731 }
00732 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, float>& map) const
00733 {
00734 return param::getCached(resolveName(key), map);
00735 }
00736 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, int>& map) const
00737 {
00738 return param::getCached(resolveName(key), map);
00739 }
00740 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, bool>& map) const
00741 {
00742 return param::getCached(resolveName(key), map);
00743 }
00744
00745 bool NodeHandle::searchParam(const std::string& key, std::string& result_out) const
00746 {
00747
00748
00749
00750 std::string remapped = key;
00751 M_string::const_iterator it = unresolved_remappings_.find(key);
00752
00753 if (it != unresolved_remappings_.end())
00754 {
00755 remapped = it->second;
00756 }
00757
00758 return param::search(resolveName(""), remapped, result_out);
00759 }
00760
00761 bool NodeHandle::ok() const
00762 {
00763 return ros::ok() && ok_;
00764 }
00765
00766 }