node_handle.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #include "ros/node_handle.h"
29 #include "ros/this_node.h"
30 #include "ros/service.h"
31 #include "ros/callback_queue.h"
32 
33 #include "ros/time.h"
34 #include "ros/rate.h"
35 #include "ros/timer.h"
36 #include "ros/wall_timer.h"
37 #include "ros/steady_timer.h"
38 
39 #include "ros/xmlrpc_manager.h"
40 #include "ros/topic_manager.h"
41 #include "ros/service_manager.h"
42 #include "ros/master.h"
43 #include "ros/param.h"
44 #include "ros/names.h"
45 #include "ros/init.h"
46 #include "ros/this_node.h"
47 #include "xmlrpcpp/XmlRpc.h"
48 
49 #include <boost/thread.hpp>
50 
51 namespace ros
52 {
53 
54 boost::mutex g_nh_refcount_mutex;
55 int32_t g_nh_refcount = 0;
56 bool g_node_started_by_nh = false;
57 
59 {
60 public:
61  typedef std::vector<Publisher::ImplWPtr> V_PubImpl;
62  typedef std::vector<ServiceServer::ImplWPtr> V_SrvImpl;
63  typedef std::vector<Subscriber::ImplWPtr> V_SubImpl;
64  typedef std::vector<ServiceClient::ImplWPtr> V_SrvCImpl;
69 
70  boost::mutex mutex_;
71 
72  // keep shared_ptrs to these managers to avoid assertions. Fixes #838
75 };
76 
77 NodeHandle::NodeHandle(const std::string& ns, const M_string& remappings)
78  : namespace_(this_node::getNamespace())
79  , callback_queue_(0)
80  , collection_(0)
81 {
82  std::string tilde_resolved_ns;
83  if (!ns.empty() && ns[0] == '~')// starts with tilde
84  tilde_resolved_ns = names::resolve(ns);
85  else
86  tilde_resolved_ns = ns;
87 
88  construct(tilde_resolved_ns, true);
89 
90  initRemappings(remappings);
91 }
92 
93 NodeHandle::NodeHandle(const NodeHandle& parent, const std::string& ns)
94 : collection_(0)
95 {
96  namespace_ = parent.getNamespace();
98 
99  remappings_ = parent.remappings_;
101 
102  construct(ns, false);
103 }
104 
105 NodeHandle::NodeHandle(const NodeHandle& parent, const std::string& ns, const M_string& remappings)
106 : collection_(0)
107 {
108  namespace_ = parent.getNamespace();
110 
111  remappings_ = parent.remappings_;
113 
114  construct(ns, false);
115 
116  initRemappings(remappings);
117 }
118 
120 : collection_(0)
121 {
123  remappings_ = rhs.remappings_;
125 
126  construct(rhs.namespace_, true);
127 
129 }
130 
132 {
133  destruct();
134 }
135 
137 {
139  namespace_ = rhs.namespace_;
141  remappings_ = rhs.remappings_;
143 
144  return *this;
145 }
146 
148 {
149  ros::spin();
150 }
151 
152 void NodeHandle::construct(const std::string& ns, bool validate_name)
153 {
154  if (!ros::isInitialized())
155  {
156  ROS_FATAL("You must call ros::init() before creating the first NodeHandle");
157  ROS_BREAK();
158  }
159 
162  // if callback_queue_ is nonnull, we are in a non-nullary constructor
163 
164  if (validate_name)
165  namespace_ = resolveName(ns, true);
166  else
167  {
168  namespace_ = resolveName(ns, true, no_validate());
169  // FIXME validate namespace_ now
170  }
171  ok_ = true;
172 
173  boost::mutex::scoped_lock lock(g_nh_refcount_mutex);
174 
175  if (g_nh_refcount == 0 && !ros::isStarted())
176  {
177  g_node_started_by_nh = true;
178  ros::start();
179  }
180 
181  ++g_nh_refcount;
182 }
183 
185 {
186  delete collection_;
187 
188  boost::mutex::scoped_lock lock(g_nh_refcount_mutex);
189 
190  --g_nh_refcount;
191 
193  {
194  ros::shutdown();
195  }
196 }
197 
198 void NodeHandle::initRemappings(const M_string& remappings)
199 {
200  {
201  M_string::const_iterator it = remappings.begin();
202  M_string::const_iterator end = remappings.end();
203  for (; it != end; ++it)
204  {
205  const std::string& from = it->first;
206  const std::string& to = it->second;
207 
208  remappings_.insert(std::make_pair(resolveName(from, false), resolveName(to, false)));
209  unresolved_remappings_.insert(std::make_pair(from, to));
210  }
211  }
212 }
213 
215 {
216  callback_queue_ = queue;
217 }
218 
219 std::string NodeHandle::remapName(const std::string& name) const
220 {
221  std::string resolved = resolveName(name, false);
222 
223  // First search any remappings that were passed in specifically for this NodeHandle
224  M_string::const_iterator it = remappings_.find(resolved);
225  if (it != remappings_.end())
226  {
227  // ROSCPP_LOG_DEBUG("found 'local' remapping: %s", it->second.c_str());
228  return it->second;
229  }
230 
231  // If not in our local remappings, perhaps in the global ones
232  return names::remap(resolved);
233 }
234 
235 std::string NodeHandle::resolveName(const std::string& name, bool remap) const
236 {
237  // ROSCPP_LOG_DEBUG("resolveName(%s, %s)", name.c_str(), remap ? "true" : "false");
238  std::string error;
239  if (!names::validate(name, error))
240  {
241  throw InvalidNameException(error);
242  }
243 
244  return resolveName(name, remap, no_validate());
245 }
246 
247 std::string NodeHandle::resolveName(const std::string& name, bool remap, no_validate) const
248 {
249  if (name.empty())
250  {
251  return namespace_;
252  }
253 
254  std::string final = name;
255 
256  if (final[0] == '~')
257  {
258  std::stringstream ss;
259  ss << "Using ~ names with NodeHandle methods is not allowed. If you want to use private names with the NodeHandle ";
260  ss << "interface, construct a NodeHandle using a private name as its namespace. e.g. ";
261  ss << "ros::NodeHandle nh(\"~\"); ";
262  ss << "nh.getParam(\"my_private_name\");";
263  ss << " (name = [" << name << "])";
264  throw InvalidNameException(ss.str());
265  }
266  else if (final[0] == '/')
267  {
268  // do nothing
269  }
270  else if (!namespace_.empty())
271  {
272  // ROSCPP_LOG_DEBUG("Appending namespace_ (%s)", namespace_.c_str());
273  final = names::append(namespace_, final);
274  }
275 
276  // ROSCPP_LOG_DEBUG("resolveName, pre-clean: %s", final.c_str());
277  final = names::clean(final);
278  // ROSCPP_LOG_DEBUG("resolveName, post-clean: %s", final.c_str());
279 
280  if (remap)
281  {
282  final = remapName(final);
283  // ROSCPP_LOG_DEBUG("resolveName, remapped: %s", final.c_str());
284  }
285 
286  return names::resolve(final, false);
287 }
288 
290 {
291  ops.topic = resolveName(ops.topic);
292  if (ops.callback_queue == 0)
293  {
294  if (callback_queue_)
295  {
297  }
298  else
299  {
301  }
302  }
303 
304  SubscriberCallbacksPtr callbacks(boost::make_shared<SubscriberCallbacks>(ops.connect_cb, ops.disconnect_cb,
305  ops.tracked_object, ops.callback_queue));
306 
307  Publisher pub(ops.topic, ops.md5sum, ops.datatype, ops.latch, *this, callbacks);
308 
309  if (ops.latch) {
310  callbacks->push_latched_message_ = pub.getLastMessageCallback();
311  }
312 
313  if (TopicManager::instance()->advertise(ops, callbacks))
314  {
315 
316  {
317  boost::mutex::scoped_lock lock(collection_->mutex_);
318  collection_->pubs_.push_back(pub.impl_);
319  }
320 
321  return pub;
322  }
323 
324  return Publisher();
325 }
326 
328 {
329  ops.topic = resolveName(ops.topic);
330  if (ops.callback_queue == 0)
331  {
332  if (callback_queue_)
333  {
335  }
336  else
337  {
339  }
340  }
341 
342  if (TopicManager::instance()->subscribe(ops))
343  {
344  Subscriber sub(ops.topic, *this, ops.helper);
345 
346  {
347  boost::mutex::scoped_lock lock(collection_->mutex_);
348  collection_->subs_.push_back(sub.impl_);
349  }
350 
351  return sub;
352  }
353 
354  return Subscriber();
355 }
356 
358 {
359  ops.service = resolveName(ops.service);
360  if (ops.callback_queue == 0)
361  {
362  if (callback_queue_)
363  {
365  }
366  else
367  {
369  }
370  }
371 
373  {
374  ServiceServer srv(ops.service, *this);
375 
376  {
377  boost::mutex::scoped_lock lock(collection_->mutex_);
378  collection_->srvs_.push_back(srv.impl_);
379  }
380 
381  return srv;
382  }
383 
384  return ServiceServer();
385 }
386 
388 {
389  ops.service = resolveName(ops.service);
390  ServiceClient client(ops.service, ops.persistent, ops.header, ops.md5sum);
391 
392  if (client)
393  {
394  boost::mutex::scoped_lock lock(collection_->mutex_);
395  collection_->srv_cs_.push_back(client.impl_);
396  }
397 
398  return client;
399 }
400 
402  bool oneshot, bool autostart) const
403 {
404  TimerOptions ops;
405  ops.period = period;
406  ops.callback = callback;
407  ops.oneshot = oneshot;
408  ops.autostart = autostart;
409  return createTimer(ops);
410 }
411 
413 {
414  if (ops.callback_queue == 0)
415  {
416  if (callback_queue_)
417  {
419  }
420  else
421  {
423  }
424  }
425 
426  Timer timer(ops);
427  if (ops.autostart)
428  timer.start();
429  return timer;
430 }
431 
433  bool oneshot, bool autostart) const
434 {
435  WallTimerOptions ops;
436  ops.period = period;
437  ops.callback = callback;
438  ops.oneshot = oneshot;
439  ops.autostart = autostart;
440  return createWallTimer(ops);
441 }
442 
444 {
445  if (ops.callback_queue == 0)
446  {
447  if (callback_queue_)
448  {
450  }
451  else
452  {
454  }
455  }
456 
457  WallTimer timer(ops);
458  if (ops.autostart)
459  timer.start();
460  return timer;
461 }
462 
464  bool oneshot, bool autostart) const
465 {
466  SteadyTimerOptions ops;
467  ops.period = period;
468  ops.callback = callback;
469  ops.oneshot = oneshot;
470  ops.autostart = autostart;
471  return createSteadyTimer(ops);
472 }
473 
475 {
476  if (ops.callback_queue == 0)
477  {
478  if (callback_queue_)
479  {
481  }
482  else
483  {
485  }
486  }
487 
488  SteadyTimer timer(ops);
489  if (ops.autostart)
490  timer.start();
491  return timer;
492 }
493 
495 {
496  {
497  NodeHandleBackingCollection::V_SubImpl::iterator it = collection_->subs_.begin();
498  NodeHandleBackingCollection::V_SubImpl::iterator end = collection_->subs_.end();
499  for (; it != end; ++it)
500  {
501  Subscriber::ImplPtr impl = it->lock();
502 
503  if (impl)
504  {
505  impl->unsubscribe();
506  }
507  }
508  }
509 
510  {
511  NodeHandleBackingCollection::V_PubImpl::iterator it = collection_->pubs_.begin();
512  NodeHandleBackingCollection::V_PubImpl::iterator end = collection_->pubs_.end();
513  for (; it != end; ++it)
514  {
515  Publisher::ImplPtr impl = it->lock();
516 
517  if (impl)
518  {
519  impl->unadvertise();
520  }
521  }
522  }
523 
524  {
525  NodeHandleBackingCollection::V_SrvImpl::iterator it = collection_->srvs_.begin();
526  NodeHandleBackingCollection::V_SrvImpl::iterator end = collection_->srvs_.end();
527  for (; it != end; ++it)
528  {
529  ServiceServer::ImplPtr impl = it->lock();
530 
531  if (impl)
532  {
533  impl->unadvertise();
534  }
535  }
536  }
537 
538  {
539  NodeHandleBackingCollection::V_SrvCImpl::iterator it = collection_->srv_cs_.begin();
540  NodeHandleBackingCollection::V_SrvCImpl::iterator end = collection_->srv_cs_.end();
541  for (; it != end; ++it)
542  {
543  ServiceClient::ImplPtr impl = it->lock();
544 
545  if (impl)
546  {
547  impl->shutdown();
548  }
549  }
550  }
551 
552  ok_ = false;
553 }
554 
555 void NodeHandle::setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const
556 {
557  return param::set(resolveName(key), v);
558 }
559 
560 void NodeHandle::setParam(const std::string& key, const std::string& s) const
561 {
562  return param::set(resolveName(key), s);
563 }
564 
565 void NodeHandle::setParam(const std::string& key, const char* s) const
566 {
567  return param::set(resolveName(key), s);
568 }
569 
570 void NodeHandle::setParam(const std::string& key, double d) const
571 {
572  return param::set(resolveName(key), d);
573 }
574 
575 void NodeHandle::setParam(const std::string& key, int i) const
576 {
577  return param::set(resolveName(key), i);
578 }
579 
580 void NodeHandle::setParam(const std::string& key, bool b) const
581 {
582  return param::set(resolveName(key), b);
583 }
584 
585 void NodeHandle::setParam(const std::string& key, const std::vector<std::string>& vec) const
586 {
587  return param::set(resolveName(key), vec);
588 }
589 void NodeHandle::setParam(const std::string& key, const std::vector<double>& vec) const
590 {
591  return param::set(resolveName(key), vec);
592 }
593 void NodeHandle::setParam(const std::string& key, const std::vector<float>& vec) const
594 {
595  return param::set(resolveName(key), vec);
596 }
597 void NodeHandle::setParam(const std::string& key, const std::vector<int>& vec) const
598 {
599  return param::set(resolveName(key), vec);
600 }
601 void NodeHandle::setParam(const std::string& key, const std::vector<bool>& vec) const
602 {
603  return param::set(resolveName(key), vec);
604 }
605 
606 void NodeHandle::setParam(const std::string& key, const std::map<std::string, std::string>& map) const
607 {
608  return param::set(resolveName(key), map);
609 }
610 void NodeHandle::setParam(const std::string& key, const std::map<std::string, double>& map) const
611 {
612  return param::set(resolveName(key), map);
613 }
614 void NodeHandle::setParam(const std::string& key, const std::map<std::string, float>& map) const
615 {
616  return param::set(resolveName(key), map);
617 }
618 void NodeHandle::setParam(const std::string& key, const std::map<std::string, int>& map) const
619 {
620  return param::set(resolveName(key), map);
621 }
622 void NodeHandle::setParam(const std::string& key, const std::map<std::string, bool>& map) const
623 {
624  return param::set(resolveName(key), map);
625 }
626 
627 bool NodeHandle::hasParam(const std::string& key) const
628 {
629  return param::has(resolveName(key));
630 }
631 
632 bool NodeHandle::deleteParam(const std::string& key) const
633 {
634  return param::del(resolveName(key));
635 }
636 
637 bool NodeHandle::getParamNames(std::vector<std::string>& keys) const
638 {
639  return param::getParamNames(keys);
640 }
641 
642 bool NodeHandle::getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const
643 {
644  return param::get(resolveName(key), v);
645 }
646 
647 bool NodeHandle::getParam(const std::string& key, std::string& s) const
648 {
649  return param::get(resolveName(key), s);
650 }
651 
652 bool NodeHandle::getParam(const std::string& key, double& d) const
653 {
654  return param::get(resolveName(key), d);
655 }
656 
657 bool NodeHandle::getParam(const std::string& key, float& f) const
658 {
659  return param::get(resolveName(key), f);
660 }
661 
662 bool NodeHandle::getParam(const std::string& key, int& i) const
663 {
664  return param::get(resolveName(key), i);
665 }
666 
667 bool NodeHandle::getParam(const std::string& key, bool& b) const
668 {
669  return param::get(resolveName(key), b);
670 }
671 
672 
673 bool NodeHandle::getParam(const std::string& key, std::vector<std::string>& vec) const
674 {
675  return param::get(resolveName(key), vec);
676 }
677 bool NodeHandle::getParam(const std::string& key, std::vector<double>& vec) const
678 {
679  return param::get(resolveName(key), vec);
680 }
681 bool NodeHandle::getParam(const std::string& key, std::vector<float>& vec) const
682 {
683  return param::get(resolveName(key), vec);
684 }
685 bool NodeHandle::getParam(const std::string& key, std::vector<int>& vec) const
686 {
687  return param::get(resolveName(key), vec);
688 }
689 bool NodeHandle::getParam(const std::string& key, std::vector<bool>& vec) const
690 {
691  return param::get(resolveName(key), vec);
692 }
693 
694 bool NodeHandle::getParam(const std::string& key, std::map<std::string, std::string>& map) const
695 {
696  return param::get(resolveName(key), map);
697 }
698 bool NodeHandle::getParam(const std::string& key, std::map<std::string, double>& map) const
699 {
700  return param::get(resolveName(key), map);
701 }
702 bool NodeHandle::getParam(const std::string& key, std::map<std::string, float>& map) const
703 {
704  return param::get(resolveName(key), map);
705 }
706 bool NodeHandle::getParam(const std::string& key, std::map<std::string, int>& map) const
707 {
708  return param::get(resolveName(key), map);
709 }
710 bool NodeHandle::getParam(const std::string& key, std::map<std::string, bool>& map) const
711 {
712  return param::get(resolveName(key), map);
713 }
714 
715 bool NodeHandle::getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const
716 {
717  return param::getCached(resolveName(key), v);
718 }
719 
720 bool NodeHandle::getParamCached(const std::string& key, std::string& s) const
721 {
722  return param::getCached(resolveName(key), s);
723 }
724 
725 bool NodeHandle::getParamCached(const std::string& key, double& d) const
726 {
727  return param::getCached(resolveName(key), d);
728 }
729 
730 bool NodeHandle::getParamCached(const std::string& key, float& f) const
731 {
732  return param::getCached(resolveName(key), f);
733 }
734 
735 bool NodeHandle::getParamCached(const std::string& key, int& i) const
736 {
737  return param::getCached(resolveName(key), i);
738 }
739 
740 bool NodeHandle::getParamCached(const std::string& key, bool& b) const
741 {
742  return param::getCached(resolveName(key), b);
743 }
744 
745 bool NodeHandle::getParamCached(const std::string& key, std::vector<std::string>& vec) const
746 {
747  return param::getCached(resolveName(key), vec);
748 }
749 bool NodeHandle::getParamCached(const std::string& key, std::vector<double>& vec) const
750 {
751  return param::getCached(resolveName(key), vec);
752 }
753 bool NodeHandle::getParamCached(const std::string& key, std::vector<float>& vec) const
754 {
755  return param::getCached(resolveName(key), vec);
756 }
757 bool NodeHandle::getParamCached(const std::string& key, std::vector<int>& vec) const
758 {
759  return param::getCached(resolveName(key), vec);
760 }
761 bool NodeHandle::getParamCached(const std::string& key, std::vector<bool>& vec) const
762 {
763  return param::getCached(resolveName(key), vec);
764 }
765 
766 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, std::string>& map) const
767 {
768  return param::getCached(resolveName(key), map);
769 }
770 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, double>& map) const
771 {
772  return param::getCached(resolveName(key), map);
773 }
774 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, float>& map) const
775 {
776  return param::getCached(resolveName(key), map);
777 }
778 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, int>& map) const
779 {
780  return param::getCached(resolveName(key), map);
781 }
782 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, bool>& map) const
783 {
784  return param::getCached(resolveName(key), map);
785 }
786 
787 bool NodeHandle::searchParam(const std::string& key, std::string& result_out) const
788 {
789  // searchParam needs a separate form of remapping -- remapping on the unresolved name, rather than the
790  // resolved one.
791 
792  std::string remapped = key;
793  M_string::const_iterator it = unresolved_remappings_.find(key);
794  // First try our local remappings
795  if (it != unresolved_remappings_.end())
796  {
797  remapped = it->second;
798  }
799 
800  return param::search(resolveName(""), remapped, result_out);
801 }
802 
803 bool NodeHandle::ok() const
804 {
805  return ros::ok() && ok_;
806 }
807 
808 } // namespace ros
this_node.h
ROS_BREAK
#define ROS_BREAK()
ros::AdvertiseOptions::topic
std::string topic
The topic to publish on.
Definition: advertise_options.h:98
ros::this_node::getNamespace
const ROSCPP_DECL std::string & getNamespace()
Returns the namespace of the current node.
Definition: this_node.cpp:79
ros::TimerOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: timer_options.h:65
ros::NodeHandle::createSteadyTimer
SteadyTimer createSteadyTimer(WallDuration period, void(T::*callback)(const SteadyTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
Create a timer which will call a callback at the specified rate, using wall time to determine when to...
Definition: node_handle.h:1489
ros::ServiceClientOptions::persistent
bool persistent
Whether or not the connection should persist.
Definition: service_client_options.h:102
ros::NodeHandle::namespace_
std::string namespace_
Definition: node_handle.h:2189
ros::TimerCallback
boost::function< void(const TimerEvent &)> TimerCallback
Definition: forwards.h:147
boost::shared_ptr< TopicManager >
ros::g_node_started_by_nh
bool g_node_started_by_nh
Definition: node_handle.cpp:56
ros::TimerOptions
Encapsulates all options available for starting a timer.
Definition: timer_options.h:40
ros::NodeHandleBackingCollection::keep_alive_topic_manager
TopicManagerPtr keep_alive_topic_manager
Definition: node_handle.cpp:73
service.h
ros::WallTimerOptions::period
WallDuration period
The period to call the callback at.
Definition: wall_timer_options.h:63
ros::NodeHandle::remapName
std::string remapName(const std::string &name) const
Definition: node_handle.cpp:219
ros::NodeHandle::construct
void construct(const std::string &ns, bool validate_name)
Definition: node_handle.cpp:152
ros::NodeHandle::NodeHandle
NodeHandle(const std::string &ns=std::string(), const M_string &remappings=M_string())
Constructor.
Definition: node_handle.cpp:77
s
XmlRpcServer s
ros
ros::AdvertiseOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: advertise_options.h:108
ros::SteadyTimerOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: steady_timer_options.h:66
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Definition: node_handle.h:879
ros::NodeHandleBackingCollection::V_PubImpl
std::vector< Publisher::ImplWPtr > V_PubImpl
Definition: node_handle.cpp:61
time.h
ros::SteadyTimerOptions::autostart
bool autostart
Definition: steady_timer_options.h:79
service_manager.h
ros::SubscribeOptions::topic
std::string topic
Topic to subscribe to.
Definition: subscribe_options.h:115
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Create a client for a service, version templated on two message types.
Definition: node_handle.h:1240
ros::NodeHandleBackingCollection::V_SrvCImpl
std::vector< ServiceClient::ImplWPtr > V_SrvCImpl
Definition: node_handle.cpp:64
wall_timer.h
ros::SteadyTimerOptions::oneshot
bool oneshot
Definition: steady_timer_options.h:78
ros::NodeHandle::deleteParam
bool deleteParam(const std::string &key) const
Delete a parameter from the parameter server.
Definition: node_handle.cpp:632
ros::names::clean
ROSCPP_DECL std::string clean(const std::string &name)
Cleans a graph resource name: removes double slashes, trailing slash.
Definition: names.cpp:99
ros::SubscribeOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: subscribe_options.h:123
ros::AdvertiseOptions::connect_cb
SubscriberStatusCallback connect_cb
The function to call when a subscriber connects to this topic.
Definition: advertise_options.h:105
ros::shutdown
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:605
ros::NodeHandle::operator=
NodeHandle & operator=(const NodeHandle &rhs)
Definition: node_handle.cpp:136
ros::ServiceClient::impl_
ImplPtr impl_
Definition: service_client.h:207
ros::ServiceManager::instance
static const ServiceManagerPtr & instance()
Definition: service_manager.cpp:55
ros::NodeHandle::createWallTimer
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
Create a timer which will call a callback at the specified rate, using wall time to determine when to...
Definition: node_handle.h:1410
ros::AdvertiseOptions::disconnect_cb
SubscriberStatusCallback disconnect_cb
The function to call when a subscriber disconnects from this topic.
Definition: advertise_options.h:106
ros::SteadyTimerOptions::period
WallDuration period
The period to call the callback at.
Definition: steady_timer_options.h:63
ros::NodeHandleBackingCollection
Definition: node_handle.cpp:58
ros::NodeHandleBackingCollection::V_SrvImpl
std::vector< ServiceServer::ImplWPtr > V_SrvImpl
Definition: node_handle.cpp:62
ros::AdvertiseOptions::datatype
std::string datatype
The datatype of the message published on this topic (eg. "std_msgs/String")
Definition: advertise_options.h:102
ros::WallTimerOptions::callback
WallTimerCallback callback
The callback to call.
Definition: wall_timer_options.h:64
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Definition: node_handle.h:402
ros::WallTimerCallback
boost::function< void(const WallTimerEvent &)> WallTimerCallback
Definition: forwards.h:167
ros::NodeHandle::unresolved_namespace_
std::string unresolved_namespace_
Definition: node_handle.h:2190
ros::names::validate
ROSCPP_DECL bool validate(const std::string &name, std::string &error)
Validate a name against the name spec.
Definition: names.cpp:66
ros::AdvertiseOptions
Encapsulates all options available for creating a Publisher.
Definition: advertise_options.h:41
ros::ok
ROSCPP_DECL bool ok()
Check whether it's time to exit.
Definition: init.cpp:600
ros::Subscriber::impl_
ImplPtr impl_
Definition: subscriber.h:111
ros::param::del
ROSCPP_DECL bool del(const std::string &key)
Delete a parameter from the parameter server.
Definition: param.cpp:228
ros::names::resolve
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
Resolve a graph resource name into a fully qualified graph resource name.
Definition: names.cpp:136
f
f
ros::Publisher::impl_
ImplPtr impl_
Definition: publisher.h:209
ros::TimerOptions::callback
TimerCallback callback
The callback to call.
Definition: timer_options.h:63
ros::TimerOptions::autostart
bool autostart
Definition: timer_options.h:78
ros::Timer
Manages a timer callback.
Definition: timer.h:46
topic_manager.h
ros::WallTimer::start
void start()
Start the timer. Does nothing if the timer is already started.
Definition: wall_timer.cpp:116
ros::WallTimer
Manages a wall-clock timer callback.
Definition: wall_timer.h:46
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
Resolves a name into a fully-qualified name.
Definition: node_handle.cpp:235
ros::WallTimerOptions
Encapsulates all options available for starting a timer.
Definition: wall_timer_options.h:40
ros::NodeHandle::callback_queue_
CallbackQueueInterface * callback_queue_
Definition: node_handle.h:2194
ros::param::getCached
ROSCPP_DECL bool getCached(const std::string &key, std::string &s)
Get a string value from the parameter server, with local caching.
Definition: param.cpp:439
ros::ServiceClientOptions::header
M_string header
Extra key/value pairs to add to the connection header.
Definition: service_client_options.h:103
ros::NodeHandleBackingCollection::keep_alive_service_manager
ServiceManagerPtr keep_alive_service_manager
Definition: node_handle.cpp:74
init.h
ros::AdvertiseServiceOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: advertise_service_options.h:126
ros::AdvertiseOptions::latch
bool latch
Whether or not this publication should "latch". A latching publication will automatically send out th...
Definition: advertise_options.h:126
timer.h
ros::NodeHandle::unresolved_remappings_
M_string unresolved_remappings_
Definition: node_handle.h:2192
ros::ServiceClientOptions
Encapsulates all options available for creating a ServiceClient.
Definition: service_client_options.h:41
param.h
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
Search up the tree for a parameter with a given key.
Definition: node_handle.cpp:787
ros::isInitialized
ROSCPP_DECL bool isInitialized()
Returns whether or not ros::init() has been called.
Definition: init.cpp:111
XmlRpc.h
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
Check whether a parameter exists on the parameter server.
Definition: node_handle.cpp:627
d
d
ros::ServiceClient
Provides a handle-based interface to service client connections.
Definition: service_client.h:42
ros::g_nh_refcount
int32_t g_nh_refcount
Definition: node_handle.cpp:55
rate.h
ros::AdvertiseServiceOptions
Encapsulates all options available for creating a ServiceServer.
Definition: advertise_service_options.h:43
ros::NodeHandle
roscpp's interface for creating subscribers, publishers, etc.
Definition: node_handle.h:87
xmlrpc_manager.h
ros::names::remap
ROSCPP_DECL std::string remap(const std::string &name)
Apply remappings to a name.
Definition: names.cpp:123
ros::NodeHandle::advertise
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Advertise a topic, simple version.
Definition: node_handle.h:249
ros::isStarted
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
Definition: init.cpp:289
ros::SteadyTimerOptions::callback
SteadyTimerCallback callback
The callback to call.
Definition: steady_timer_options.h:64
ros::Publisher
Manages an advertisement on a specific topic.
Definition: publisher.h:48
ros::NodeHandle::setParam
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
Set an arbitrary XML/RPC value on the parameter server.
Definition: node_handle.cpp:555
ROS_FATAL
#define ROS_FATAL(...)
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
Set the default callback queue to be used by this NodeHandle.
Definition: node_handle.cpp:214
ros::NodeHandle::getParam
bool getParam(const std::string &key, std::string &s) const
Get a string value from the parameter server.
Definition: node_handle.cpp:647
ros::TimerOptions::period
Duration period
The period to call the callback at.
Definition: timer_options.h:62
ros::NodeHandle::getParamCached
bool getParamCached(const std::string &key, std::string &s) const
Get a string value from the parameter server, with local caching.
Definition: node_handle.cpp:720
ros::g_nh_refcount_mutex
boost::mutex g_nh_refcount_mutex
Definition: node_handle.cpp:54
ros::NodeHandleBackingCollection::V_SubImpl
std::vector< Subscriber::ImplWPtr > V_SubImpl
Definition: node_handle.cpp:63
ros::SteadyTimerCallback
boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
Definition: forwards.h:187
ros::AdvertiseServiceOptions::service
std::string service
Service name.
Definition: advertise_service_options.h:118
ros::ServiceClientOptions::md5sum
std::string md5sum
Service md5sum.
Definition: service_client_options.h:101
ros::start
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
Definition: init.cpp:294
ros::NodeHandle::ok
bool ok() const
Check whether it's time to exit.
Definition: node_handle.cpp:803
ros::names::append
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
Append one name to another.
Definition: names.cpp:118
ros::WallTimerOptions::autostart
bool autostart
Definition: wall_timer_options.h:79
ros::SubscribeOptions
Encapsulates all options available for creating a Subscriber.
Definition: subscribe_options.h:43
ros::NodeHandle::getParamNames
bool getParamNames(std::vector< std::string > &keys) const
Get the keys for all the parameters in the parameter server.
Definition: node_handle.cpp:637
master.h
ros::SteadyTimer::start
void start()
Start the timer. Does nothing if the timer is already started.
Definition: steady_timer.cpp:116
ros::WallTimerOptions::callback_queue
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: wall_timer_options.h:66
ros::TopicManager::instance
static const TopicManagerPtr & instance()
Definition: topic_manager.cpp:56
ros::NodeHandle::initRemappings
void initRemappings(const M_string &remappings)
Definition: node_handle.cpp:198
ros::param::get
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Get a string value from the parameter server.
Definition: param.cpp:409
ros::param::search
ROSCPP_DECL bool search(const std::string &ns, const std::string &key, std::string &result)
Search up the tree for a parameter with a given key.
Definition: param.cpp:752
ros::spinThread
void spinThread()
Definition: node_handle.cpp:147
ros::Publisher::getLastMessageCallback
boost::function< void(const SubscriberLinkPtr &)> getLastMessageCallback()
Definition: publisher.h:173
ros::InvalidNameException
Thrown when an invalid graph resource name is specified to any roscpp function.
Definition: exceptions.h:51
ros::SteadyTimerOptions
Encapsulates all options available for starting a timer.
Definition: steady_timer_options.h:40
ros::NodeHandleBackingCollection::srv_cs_
V_SrvCImpl srv_cs_
Definition: node_handle.cpp:68
ros::WallTimerOptions::oneshot
bool oneshot
Definition: wall_timer_options.h:78
ros::ServiceServer::impl_
ImplPtr impl_
Definition: service_server.h:102
ros::param::getParamNames
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
Definition: param.cpp:717
ros::NodeHandle::~NodeHandle
~NodeHandle()
Destructor.
Definition: node_handle.cpp:131
ros::AdvertiseOptions::md5sum
std::string md5sum
The md5sum of the message datatype published on this topic.
Definition: advertise_options.h:101
ros::spin
ROSCPP_DECL void spin()
Enter simple event loop.
Definition: init.cpp:571
ros::ServiceServer
Manages an service advertisement.
Definition: service_server.h:45
ros::NodeHandleBackingCollection::srvs_
V_SrvImpl srvs_
Definition: node_handle.cpp:66
ros::NodeHandleBackingCollection::subs_
V_SubImpl subs_
Definition: node_handle.cpp:67
ros::param::has
ROSCPP_DECL bool has(const std::string &key)
Check whether a parameter exists on the parameter server.
Definition: param.cpp:211
callback_queue.h
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
Returns the namespace associated with this NodeHandle.
Definition: node_handle.h:191
ros::NodeHandle::remappings_
M_string remappings_
Definition: node_handle.h:2191
names.h
ros::WallDuration
ros::Timer::start
void start()
Start the timer. Does nothing if the timer is already started.
Definition: timer.cpp:121
ros::SubscribeOptions::helper
SubscriptionCallbackHelperPtr helper
Helper object used to get create messages and call callbacks.
Definition: subscribe_options.h:121
ros::Subscriber
Manages an subscription callback on a specific topic.
Definition: subscriber.h:46
ros::NodeHandle::shutdown
void shutdown()
Shutdown every handle created through this NodeHandle.
Definition: node_handle.cpp:494
ros::AdvertiseOptions::tracked_object
VoidConstPtr tracked_object
An object whose destruction will prevent the callbacks associated with this advertisement from being ...
Definition: advertise_options.h:120
ROS_ASSERT
#define ROS_ASSERT(cond)
ros::NodeHandleBackingCollection::mutex_
boost::mutex mutex_
Definition: node_handle.cpp:70
ros::NodeHandle::destruct
void destruct()
Definition: node_handle.cpp:184
ros::Duration
node_handle.h
steady_timer.h
ros::SteadyTimer
Manages a steady-clock timer callback.
Definition: steady_timer.h:46
ros::TimerOptions::oneshot
bool oneshot
Definition: timer_options.h:77
XmlRpc::XmlRpcValue
ros::CallbackQueueInterface
Abstract interface for a queue used to handle all callbacks within roscpp.
Definition: callback_queue_interface.h:82
ros::ServiceClientOptions::service
std::string service
Service to connect to.
Definition: service_client_options.h:100
ros::NodeHandle::collection_
NodeHandleBackingCollection * collection_
Definition: node_handle.h:2196
ros::NodeHandle::no_validate
Definition: node_handle.h:2178
ros::NodeHandle::ok_
bool ok_
Definition: node_handle.h:2198
ros::getGlobalCallbackQueue
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
Definition: init.cpp:595
ros::M_string
std::map< std::string, std::string > M_string
ros::param::set
ROSCPP_DECL void set(const std::string &key, const XmlRpc::XmlRpcValue &v)
Set an arbitrary XML/RPC value on the parameter server.
Definition: param.cpp:67
ros::NodeHandleBackingCollection::pubs_
V_PubImpl pubs_
Definition: node_handle.cpp:65
ros::NodeHandle::createTimer
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Create a timer which will call a callback at the specified rate. This variant takes a class member fu...
Definition: node_handle.h:1294


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:44