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