$search
00001 /* 00002 * Copyright (C) 2009, Willow Garage, Inc. 00003 * 00004 * Redistribution and use in source and binary forms, with or without 00005 * modification, are permitted provided that the following conditions are met: 00006 * * Redistributions of source code must retain the above copyright notice, 00007 * this list of conditions and the following disclaimer. 00008 * * Redistributions in binary form must reproduce the above copyright 00009 * notice, this list of conditions and the following disclaimer in the 00010 * documentation and/or other materials provided with the distribution. 00011 * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its 00012 * contributors may be used to endorse or promote products derived from 00013 * this software without specific prior written permission. 00014 * 00015 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00016 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00017 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00018 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00019 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00020 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00021 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00022 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00023 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00024 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00025 * POSSIBILITY OF SUCH DAMAGE. 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] == '~')// starts with tilde 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 // if callback_queue_ is nonnull, we are in a non-nullary constructor 00157 00158 if (validate_name) 00159 namespace_ = resolveName(ns, true); 00160 else 00161 { 00162 namespace_ = resolveName(ns, true, no_validate()); 00163 // FIXME validate namespace_ now 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 // First search any remappings that were passed in specifically for this NodeHandle 00218 M_string::const_iterator it = remappings_.find(resolved); 00219 if (it != remappings_.end()) 00220 { 00221 // ROSCPP_LOG_DEBUG("found 'local' remapping: %s", it->second.c_str()); 00222 return it->second; 00223 } 00224 00225 // If not in our local remappings, perhaps in the global ones 00226 return names::remap(resolved); 00227 } 00228 00229 std::string NodeHandle::resolveName(const std::string& name, bool remap) const 00230 { 00231 // ROSCPP_LOG_DEBUG("resolveName(%s, %s)", name.c_str(), remap ? "true" : "false"); 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 // do nothing 00263 } 00264 else if (!namespace_.empty()) 00265 { 00266 // ROSCPP_LOG_DEBUG("Appending namespace_ (%s)", namespace_.c_str()); 00267 final = names::append(namespace_, final); 00268 } 00269 00270 // ROSCPP_LOG_DEBUG("resolveName, pre-clean: %s", final.c_str()); 00271 final = names::clean(final); 00272 // ROSCPP_LOG_DEBUG("resolveName, post-clean: %s", final.c_str()); 00273 00274 if (remap) 00275 { 00276 final = remapName(final); 00277 // ROSCPP_LOG_DEBUG("resolveName, remapped: %s", final.c_str()); 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(new 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 bool NodeHandle::hasParam(const std::string &key) const 00544 { 00545 return param::has(resolveName(key)); 00546 } 00547 00548 bool NodeHandle::deleteParam(const std::string &key) const 00549 { 00550 return param::del(resolveName(key)); 00551 } 00552 00553 bool NodeHandle::getParam(const std::string &key, XmlRpc::XmlRpcValue &v) const 00554 { 00555 return param::get(resolveName(key), v); 00556 } 00557 00558 bool NodeHandle::getParam(const std::string &key, std::string &s) const 00559 { 00560 return param::get(resolveName(key), s); 00561 } 00562 00563 bool NodeHandle::getParam(const std::string &key, double &d) const 00564 { 00565 return param::get(resolveName(key), d); 00566 } 00567 00568 bool NodeHandle::getParam(const std::string &key, int &i) const 00569 { 00570 return param::get(resolveName(key), i); 00571 } 00572 00573 bool NodeHandle::getParam(const std::string &key, bool &b) const 00574 { 00575 return param::get(resolveName(key), b); 00576 } 00577 00578 bool NodeHandle::getParamCached(const std::string &key, XmlRpc::XmlRpcValue &v) const 00579 { 00580 return param::getCached(resolveName(key), v); 00581 } 00582 00583 bool NodeHandle::getParamCached(const std::string &key, std::string &s) const 00584 { 00585 return param::getCached(resolveName(key), s); 00586 } 00587 00588 bool NodeHandle::getParamCached(const std::string &key, double &d) const 00589 { 00590 return param::getCached(resolveName(key), d); 00591 } 00592 00593 bool NodeHandle::getParamCached(const std::string &key, int &i) const 00594 { 00595 return param::getCached(resolveName(key), i); 00596 } 00597 00598 bool NodeHandle::getParamCached(const std::string &key, bool &b) const 00599 { 00600 return param::getCached(resolveName(key), b); 00601 } 00602 00603 bool NodeHandle::searchParam(const std::string &key, std::string& result_out) const 00604 { 00605 // searchParam needs a separate form of remapping -- remapping on the unresolved name, rather than the 00606 // resolved one. 00607 00608 std::string remapped = key; 00609 M_string::const_iterator it = unresolved_remappings_.find(key); 00610 // First try our local remappings 00611 if (it != unresolved_remappings_.end()) 00612 { 00613 remapped = it->second; 00614 } 00615 00616 return param::search(resolveName(""), remapped, result_out); 00617 } 00618 00619 bool NodeHandle::ok() const 00620 { 00621 return ros::ok() && ok_; 00622 } 00623 00624 } // namespace ros