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;
65  V_PubImpl pubs_;
66  V_SrvImpl srvs_;
67  V_SubImpl subs_;
68  V_SrvCImpl srv_cs_;
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 
192  if (g_nh_refcount == 0 && g_node_started_by_nh)
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  if (TopicManager::instance()->advertise(ops, callbacks))
308  {
309  Publisher pub(ops.topic, ops.md5sum, ops.datatype, *this, callbacks);
310 
311  {
312  boost::mutex::scoped_lock lock(collection_->mutex_);
313  collection_->pubs_.push_back(pub.impl_);
314  }
315 
316  return pub;
317  }
318 
319  return Publisher();
320 }
321 
323 {
324  ops.topic = resolveName(ops.topic);
325  if (ops.callback_queue == 0)
326  {
327  if (callback_queue_)
328  {
330  }
331  else
332  {
334  }
335  }
336 
337  if (TopicManager::instance()->subscribe(ops))
338  {
339  Subscriber sub(ops.topic, *this, ops.helper);
340 
341  {
342  boost::mutex::scoped_lock lock(collection_->mutex_);
343  collection_->subs_.push_back(sub.impl_);
344  }
345 
346  return sub;
347  }
348 
349  return Subscriber();
350 }
351 
353 {
354  ops.service = resolveName(ops.service);
355  if (ops.callback_queue == 0)
356  {
357  if (callback_queue_)
358  {
360  }
361  else
362  {
364  }
365  }
366 
368  {
369  ServiceServer srv(ops.service, *this);
370 
371  {
372  boost::mutex::scoped_lock lock(collection_->mutex_);
373  collection_->srvs_.push_back(srv.impl_);
374  }
375 
376  return srv;
377  }
378 
379  return ServiceServer();
380 }
381 
383 {
384  ops.service = resolveName(ops.service);
385  ServiceClient client(ops.service, ops.persistent, ops.header, ops.md5sum);
386 
387  if (client)
388  {
389  boost::mutex::scoped_lock lock(collection_->mutex_);
390  collection_->srv_cs_.push_back(client.impl_);
391  }
392 
393  return client;
394 }
395 
397  bool oneshot, bool autostart) const
398 {
399  TimerOptions ops;
400  ops.period = period;
401  ops.callback = callback;
402  ops.oneshot = oneshot;
403  ops.autostart = autostart;
404  return createTimer(ops);
405 }
406 
408 {
409  if (ops.callback_queue == 0)
410  {
411  if (callback_queue_)
412  {
414  }
415  else
416  {
418  }
419  }
420 
421  Timer timer(ops);
422  if (ops.autostart)
423  timer.start();
424  return timer;
425 }
426 
428  bool oneshot, bool autostart) const
429 {
430  WallTimerOptions ops;
431  ops.period = period;
432  ops.callback = callback;
433  ops.oneshot = oneshot;
434  ops.autostart = autostart;
435  return createWallTimer(ops);
436 }
437 
439 {
440  if (ops.callback_queue == 0)
441  {
442  if (callback_queue_)
443  {
445  }
446  else
447  {
449  }
450  }
451 
452  WallTimer timer(ops);
453  if (ops.autostart)
454  timer.start();
455  return timer;
456 }
457 
459  bool oneshot, bool autostart) const
460 {
461  SteadyTimerOptions ops;
462  ops.period = period;
463  ops.callback = callback;
464  ops.oneshot = oneshot;
465  ops.autostart = autostart;
466  return createSteadyTimer(ops);
467 }
468 
470 {
471  if (ops.callback_queue == 0)
472  {
473  if (callback_queue_)
474  {
476  }
477  else
478  {
480  }
481  }
482 
483  SteadyTimer timer(ops);
484  if (ops.autostart)
485  timer.start();
486  return timer;
487 }
488 
490 {
491  {
492  NodeHandleBackingCollection::V_SubImpl::iterator it = collection_->subs_.begin();
493  NodeHandleBackingCollection::V_SubImpl::iterator end = collection_->subs_.end();
494  for (; it != end; ++it)
495  {
496  Subscriber::ImplPtr impl = it->lock();
497 
498  if (impl)
499  {
500  impl->unsubscribe();
501  }
502  }
503  }
504 
505  {
506  NodeHandleBackingCollection::V_PubImpl::iterator it = collection_->pubs_.begin();
507  NodeHandleBackingCollection::V_PubImpl::iterator end = collection_->pubs_.end();
508  for (; it != end; ++it)
509  {
510  Publisher::ImplPtr impl = it->lock();
511 
512  if (impl)
513  {
514  impl->unadvertise();
515  }
516  }
517  }
518 
519  {
520  NodeHandleBackingCollection::V_SrvImpl::iterator it = collection_->srvs_.begin();
521  NodeHandleBackingCollection::V_SrvImpl::iterator end = collection_->srvs_.end();
522  for (; it != end; ++it)
523  {
524  ServiceServer::ImplPtr impl = it->lock();
525 
526  if (impl)
527  {
528  impl->unadvertise();
529  }
530  }
531  }
532 
533  {
534  NodeHandleBackingCollection::V_SrvCImpl::iterator it = collection_->srv_cs_.begin();
535  NodeHandleBackingCollection::V_SrvCImpl::iterator end = collection_->srv_cs_.end();
536  for (; it != end; ++it)
537  {
538  ServiceClient::ImplPtr impl = it->lock();
539 
540  if (impl)
541  {
542  impl->shutdown();
543  }
544  }
545  }
546 
547  ok_ = false;
548 }
549 
550 void NodeHandle::setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const
551 {
552  return param::set(resolveName(key), v);
553 }
554 
555 void NodeHandle::setParam(const std::string& key, const std::string& s) const
556 {
557  return param::set(resolveName(key), s);
558 }
559 
560 void NodeHandle::setParam(const std::string& key, const char* s) const
561 {
562  return param::set(resolveName(key), s);
563 }
564 
565 void NodeHandle::setParam(const std::string& key, double d) const
566 {
567  return param::set(resolveName(key), d);
568 }
569 
570 void NodeHandle::setParam(const std::string& key, int i) const
571 {
572  return param::set(resolveName(key), i);
573 }
574 
575 void NodeHandle::setParam(const std::string& key, bool b) const
576 {
577  return param::set(resolveName(key), b);
578 }
579 
580 void NodeHandle::setParam(const std::string& key, const std::vector<std::string>& vec) const
581 {
582  return param::set(resolveName(key), vec);
583 }
584 void NodeHandle::setParam(const std::string& key, const std::vector<double>& vec) const
585 {
586  return param::set(resolveName(key), vec);
587 }
588 void NodeHandle::setParam(const std::string& key, const std::vector<float>& vec) const
589 {
590  return param::set(resolveName(key), vec);
591 }
592 void NodeHandle::setParam(const std::string& key, const std::vector<int>& vec) const
593 {
594  return param::set(resolveName(key), vec);
595 }
596 void NodeHandle::setParam(const std::string& key, const std::vector<bool>& vec) const
597 {
598  return param::set(resolveName(key), vec);
599 }
600 
601 void NodeHandle::setParam(const std::string& key, const std::map<std::string, std::string>& map) const
602 {
603  return param::set(resolveName(key), map);
604 }
605 void NodeHandle::setParam(const std::string& key, const std::map<std::string, double>& map) const
606 {
607  return param::set(resolveName(key), map);
608 }
609 void NodeHandle::setParam(const std::string& key, const std::map<std::string, float>& map) const
610 {
611  return param::set(resolveName(key), map);
612 }
613 void NodeHandle::setParam(const std::string& key, const std::map<std::string, int>& map) const
614 {
615  return param::set(resolveName(key), map);
616 }
617 void NodeHandle::setParam(const std::string& key, const std::map<std::string, bool>& map) const
618 {
619  return param::set(resolveName(key), map);
620 }
621 
622 bool NodeHandle::hasParam(const std::string& key) const
623 {
624  return param::has(resolveName(key));
625 }
626 
627 bool NodeHandle::deleteParam(const std::string& key) const
628 {
629  return param::del(resolveName(key));
630 }
631 
632 bool NodeHandle::getParamNames(std::vector<std::string>& keys) const
633 {
634  return param::getParamNames(keys);
635 }
636 
637 bool NodeHandle::getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const
638 {
639  return param::get(resolveName(key), v);
640 }
641 
642 bool NodeHandle::getParam(const std::string& key, std::string& s) const
643 {
644  return param::get(resolveName(key), s);
645 }
646 
647 bool NodeHandle::getParam(const std::string& key, double& d) const
648 {
649  return param::get(resolveName(key), d);
650 }
651 
652 bool NodeHandle::getParam(const std::string& key, float& f) const
653 {
654  return param::get(resolveName(key), f);
655 }
656 
657 bool NodeHandle::getParam(const std::string& key, int& i) const
658 {
659  return param::get(resolveName(key), i);
660 }
661 
662 bool NodeHandle::getParam(const std::string& key, bool& b) const
663 {
664  return param::get(resolveName(key), b);
665 }
666 
667 
668 bool NodeHandle::getParam(const std::string& key, std::vector<std::string>& vec) const
669 {
670  return param::get(resolveName(key), vec);
671 }
672 bool NodeHandle::getParam(const std::string& key, std::vector<double>& vec) const
673 {
674  return param::get(resolveName(key), vec);
675 }
676 bool NodeHandle::getParam(const std::string& key, std::vector<float>& vec) const
677 {
678  return param::get(resolveName(key), vec);
679 }
680 bool NodeHandle::getParam(const std::string& key, std::vector<int>& vec) const
681 {
682  return param::get(resolveName(key), vec);
683 }
684 bool NodeHandle::getParam(const std::string& key, std::vector<bool>& vec) const
685 {
686  return param::get(resolveName(key), vec);
687 }
688 
689 bool NodeHandle::getParam(const std::string& key, std::map<std::string, std::string>& map) const
690 {
691  return param::get(resolveName(key), map);
692 }
693 bool NodeHandle::getParam(const std::string& key, std::map<std::string, double>& map) const
694 {
695  return param::get(resolveName(key), map);
696 }
697 bool NodeHandle::getParam(const std::string& key, std::map<std::string, float>& map) const
698 {
699  return param::get(resolveName(key), map);
700 }
701 bool NodeHandle::getParam(const std::string& key, std::map<std::string, int>& map) const
702 {
703  return param::get(resolveName(key), map);
704 }
705 bool NodeHandle::getParam(const std::string& key, std::map<std::string, bool>& map) const
706 {
707  return param::get(resolveName(key), map);
708 }
709 
710 bool NodeHandle::getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const
711 {
712  return param::getCached(resolveName(key), v);
713 }
714 
715 bool NodeHandle::getParamCached(const std::string& key, std::string& s) const
716 {
717  return param::getCached(resolveName(key), s);
718 }
719 
720 bool NodeHandle::getParamCached(const std::string& key, double& d) const
721 {
722  return param::getCached(resolveName(key), d);
723 }
724 
725 bool NodeHandle::getParamCached(const std::string& key, float& f) const
726 {
727  return param::getCached(resolveName(key), f);
728 }
729 
730 bool NodeHandle::getParamCached(const std::string& key, int& i) const
731 {
732  return param::getCached(resolveName(key), i);
733 }
734 
735 bool NodeHandle::getParamCached(const std::string& key, bool& b) const
736 {
737  return param::getCached(resolveName(key), b);
738 }
739 
740 bool NodeHandle::getParamCached(const std::string& key, std::vector<std::string>& vec) const
741 {
742  return param::getCached(resolveName(key), vec);
743 }
744 bool NodeHandle::getParamCached(const std::string& key, std::vector<double>& vec) const
745 {
746  return param::getCached(resolveName(key), vec);
747 }
748 bool NodeHandle::getParamCached(const std::string& key, std::vector<float>& vec) const
749 {
750  return param::getCached(resolveName(key), vec);
751 }
752 bool NodeHandle::getParamCached(const std::string& key, std::vector<int>& vec) const
753 {
754  return param::getCached(resolveName(key), vec);
755 }
756 bool NodeHandle::getParamCached(const std::string& key, std::vector<bool>& vec) const
757 {
758  return param::getCached(resolveName(key), vec);
759 }
760 
761 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, std::string>& map) const
762 {
763  return param::getCached(resolveName(key), map);
764 }
765 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, double>& map) const
766 {
767  return param::getCached(resolveName(key), map);
768 }
769 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, float>& map) const
770 {
771  return param::getCached(resolveName(key), map);
772 }
773 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, int>& map) const
774 {
775  return param::getCached(resolveName(key), map);
776 }
777 bool NodeHandle::getParamCached(const std::string& key, std::map<std::string, bool>& map) const
778 {
779  return param::getCached(resolveName(key), map);
780 }
781 
782 bool NodeHandle::searchParam(const std::string& key, std::string& result_out) const
783 {
784  // searchParam needs a separate form of remapping -- remapping on the unresolved name, rather than the
785  // resolved one.
786 
787  std::string remapped = key;
788  M_string::const_iterator it = unresolved_remappings_.find(key);
789  // First try our local remappings
790  if (it != unresolved_remappings_.end())
791  {
792  remapped = it->second;
793  }
794 
795  return param::search(resolveName(""), remapped, result_out);
796 }
797 
798 bool NodeHandle::ok() const
799 {
800  return ros::ok() && ok_;
801 }
802 
803 } // namespace ros
SubscriberStatusCallback connect_cb
The function to call when a subscriber connects to this topic.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
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
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
Definition: param.cpp:727
Manages an subscription callback on a specific topic.
Definition: subscriber.h:46
#define ROS_FATAL(...)
Encapsulates all options available for creating a ServiceClient.
void start()
Start the timer. Does nothing if the timer is already started.
NodeHandle & operator=(const NodeHandle &rhs)
ROSCPP_DECL void start()
Actually starts the internals of the node (spins up threads, starts the network polling and xmlrpc lo...
Definition: init.cpp:293
void spinThread()
std::vector< ServiceServer::ImplWPtr > V_SrvImpl
Definition: node_handle.cpp:62
std::string md5sum
Service md5sum.
SubscriberStatusCallback disconnect_cb
The function to call when a subscriber disconnects from this topic.
boost::function< void(const TimerEvent &)> TimerCallback
Definition: forwards.h:144
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for class member function with bare pointer.
Definition: node_handle.h:402
std::string namespace_
Definition: node_handle.h:2189
bool getParamCached(const std::string &key, std::string &s) const
Get a string value from the parameter server, with local caching.
NodeHandle(const std::string &ns=std::string(), const M_string &remappings=M_string())
Constructor.
Definition: node_handle.cpp:77
bool deleteParam(const std::string &key) const
Delete a parameter from the parameter server.
Encapsulates all options available for starting a timer.
std::string resolveName(const std::string &name, bool remap=true) const
Resolves a name into a fully-qualified name.
WallTimerCallback callback
The callback to call.
std::vector< ServiceClient::ImplWPtr > V_SrvCImpl
Definition: node_handle.cpp:64
ROSCPP_DECL bool isInitialized()
Returns whether or not ros::init() has been called.
Definition: init.cpp:110
std::vector< Publisher::ImplWPtr > V_PubImpl
Definition: node_handle.cpp:61
CallbackQueueInterface * callback_queue_
Definition: node_handle.h:2194
void construct(const std::string &ns, bool validate_name)
std::string unresolved_namespace_
Definition: node_handle.h:2190
void start()
Start the timer. Does nothing if the timer is already started.
Definition: timer.cpp:121
SteadyTimerCallback callback
The callback to call.
ROSCPP_DECL bool validate(const std::string &name, std::string &error)
Validate a name against the name spec.
Definition: names.cpp:66
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
Definition: timer_options.h:65
TopicManagerPtr keep_alive_topic_manager
Definition: node_handle.cpp:73
ServiceManagerPtr keep_alive_service_manager
Definition: node_handle.cpp:74
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
ROSCPP_DECL std::string clean(const std::string &name)
Cleans a graph resource name: removes double slashes, trailing slash.
Definition: names.cpp:99
Abstract interface for a queue used to handle all callbacks within roscpp.
Encapsulates all options available for creating a Publisher.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Advertise a service, version for class member function with bare pointer.
Definition: node_handle.h:879
WallDuration period
The period to call the callback at.
static const ServiceManagerPtr & instance()
Encapsulates all options available for creating a ServiceServer.
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
Definition: init.cpp:568
std::map< std::string, std::string > M_string
std::string service
Service to connect to.
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
ROSCPP_DECL std::string remap(const std::string &name)
Apply remappings to a name.
Definition: names.cpp:123
void start()
Start the timer. Does nothing if the timer is already started.
Definition: wall_timer.cpp:111
SubscriptionCallbackHelperPtr helper
Helper object used to get create messages and call callbacks.
ROSCPP_DECL const std::string & getNamespace()
Returns the namespace of the current node.
Definition: this_node.cpp:86
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
VoidConstPtr tracked_object
An object whose destruction will prevent the callbacks associated with this advertisement from being ...
ImplPtr impl_
Definition: publisher.h:193
M_string unresolved_remappings_
Definition: node_handle.h:2192
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Get a string value from the parameter server.
Definition: param.cpp:419
Encapsulates all options available for creating a Subscriber.
boost::mutex g_nh_refcount_mutex
Definition: node_handle.cpp:54
bool searchParam(const std::string &key, std::string &result) const
Search up the tree for a parameter with a given key.
bool persistent
Whether or not the connection should persist.
void setCallbackQueue(CallbackQueueInterface *queue)
Set the default callback queue to be used by this NodeHandle.
roscpp&#39;s interface for creating subscribers, publishers, etc.
Definition: node_handle.h:87
boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
Definition: forwards.h:180
ROSCPP_DECL bool ok()
Check whether it&#39;s time to exit.
Definition: init.cpp:573
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
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
TimerCallback callback
The callback to call.
Definition: timer_options.h:63
const std::string & getNamespace() const
Returns the namespace associated with this NodeHandle.
Definition: node_handle.h:191
std::string datatype
The datatype of the message published on this topic (eg. "std_msgs/String")
Encapsulates all options available for starting a timer.
Definition: timer_options.h:40
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
WallDuration period
The period to call the callback at.
ROSCPP_DECL bool has(const std::string &key)
Check whether a parameter exists on the parameter server.
Definition: param.cpp:211
bool getParamNames(std::vector< std::string > &keys) const
Get the keys for all the parameters in the parameter server.
std::vector< Subscriber::ImplWPtr > V_SubImpl
Definition: node_handle.cpp:63
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Advertise a topic, simple version.
Definition: node_handle.h:249
ROSCPP_DECL void spin()
Enter simple event loop.
Definition: init.cpp:544
Manages an advertisement on a specific topic.
Definition: publisher.h:47
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:449
~NodeHandle()
Destructor.
std::string md5sum
The md5sum of the message datatype published on this topic.
Manages a steady-clock timer callback.
Definition: steady_timer.h:46
int32_t g_nh_refcount
Definition: node_handle.cpp:55
void initRemappings(const M_string &remappings)
bool g_node_started_by_nh
Definition: node_handle.cpp:56
ROSCPP_DECL bool del(const std::string &key)
Delete a parameter from the parameter server.
Definition: param.cpp:228
boost::function< void(const WallTimerEvent &)> WallTimerCallback
Definition: forwards.h:162
ROSCPP_DECL bool isStarted()
Returns whether or not the node has been started through ros::start()
Definition: init.cpp:288
Manages an service advertisement.
Duration period
The period to call the callback at.
Definition: timer_options.h:62
Thrown when an invalid graph resource name is specified to any roscpp function.
Definition: exceptions.h:51
bool getParam(const std::string &key, std::string &s) const
Get a string value from the parameter server.
void shutdown()
Shutdown every handle created through this NodeHandle.
M_string remappings_
Definition: node_handle.h:2191
std::string topic
The topic to publish on.
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
Append one name to another.
Definition: names.cpp:118
Manages a timer callback.
Definition: timer.h:46
Provides a handle-based interface to service client connections.
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:578
bool ok() const
Check whether it&#39;s time to exit.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
bool hasParam(const std::string &key) const
Check whether a parameter exists on the parameter server.
#define ROS_ASSERT(cond)
std::string topic
Topic to subscribe to.
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
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:762
#define ROS_BREAK()
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
Set an arbitrary XML/RPC value on the parameter server.
Manages a wall-clock timer callback.
Definition: wall_timer.h:46
std::string remapName(const std::string &name) const
CallbackQueueInterface * callback_queue
Queue to add callbacks to. If NULL, the global callback queue will be used.
NodeHandleBackingCollection * collection_
Definition: node_handle.h:2196
Encapsulates all options available for starting a timer.
M_string header
Extra key/value pairs to add to the connection header.
static const TopicManagerPtr & instance()


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:26