node_handle.h
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 #ifndef ROSCPP_NODE_HANDLE_H
29 #define ROSCPP_NODE_HANDLE_H
30 
31 #include "ros/forwards.h"
32 #include "ros/publisher.h"
33 #include "ros/subscriber.h"
34 #include "ros/service_server.h"
35 #include "ros/service_client.h"
36 #include "ros/timer.h"
37 #include "ros/rate.h"
38 #include "ros/wall_timer.h"
39 #include "ros/steady_timer.h"
40 #include "ros/advertise_options.h"
42 #include "ros/subscribe_options.h"
44 #include "ros/timer_options.h"
45 #include "ros/wall_timer_options.h"
46 #include "ros/spinner.h"
47 #include "ros/init.h"
48 #include "common.h"
49 
50 #include <boost/bind.hpp>
51 
52 #include <xmlrpcpp/XmlRpcValue.h>
53 
54 namespace ros
55 {
56 
57  class NodeHandleBackingCollection;
58 
87  class ROSCPP_DECL NodeHandle
88  {
89  public:
104  NodeHandle(const std::string& ns = std::string(), const M_string& remappings = M_string());
112  NodeHandle(const NodeHandle& rhs);
134  NodeHandle(const NodeHandle& parent, const std::string& ns);
156  NodeHandle(const NodeHandle& parent, const std::string& ns, const M_string& remappings);
164  ~NodeHandle();
165 
166  NodeHandle& operator=(const NodeHandle& rhs);
167 
176  void setCallbackQueue(CallbackQueueInterface* queue);
177 
184  {
185  return callback_queue_ ? callback_queue_ : (CallbackQueueInterface*)getGlobalCallbackQueue();
186  }
187 
191  const std::string& getNamespace() const { return namespace_; }
192 
197  const std::string& getUnresolvedNamespace() const { return unresolved_namespace_; }
198 
215  std::string resolveName(const std::string& name, bool remap = true) const;
216 
218  // Versions of advertise()
220 
248  template <class M>
249  Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false)
250  {
251  AdvertiseOptions ops;
252  ops.template init<M>(topic, queue_size);
253  ops.latch = latch;
254  return advertise(ops);
255  }
256 
314  template <class M>
315  Publisher advertise(const std::string& topic, uint32_t queue_size,
316  const SubscriberStatusCallback& connect_cb,
317  const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
318  const VoidConstPtr& tracked_object = VoidConstPtr(),
319  bool latch = false)
320  {
321  AdvertiseOptions ops;
322  ops.template init<M>(topic, queue_size, connect_cb, disconnect_cb);
323  ops.tracked_object = tracked_object;
324  ops.latch = latch;
325  return advertise(ops);
326  }
327 
353  Publisher advertise(AdvertiseOptions& ops);
354 
355 
357  // Versions of subscribe()
359 
401  template<class M, class T>
402  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), T* obj,
403  const TransportHints& transport_hints = TransportHints())
404  {
405  SubscribeOptions ops;
406  ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
407  ops.transport_hints = transport_hints;
408  return subscribe(ops);
409  }
410 
412  template<class M, class T>
413  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const, T* obj,
414  const TransportHints& transport_hints = TransportHints())
415  {
416  SubscribeOptions ops;
417  ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
418  ops.transport_hints = transport_hints;
419  return subscribe(ops);
420  }
421 
464  template<class M, class T>
465  Subscriber subscribe(const std::string& topic, uint32_t queue_size,
466  void(T::*fp)(const boost::shared_ptr<M const>&), T* obj,
467  const TransportHints& transport_hints = TransportHints())
468  {
469  SubscribeOptions ops;
470  ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
471  ops.transport_hints = transport_hints;
472  return subscribe(ops);
473  }
474  template<class M, class T>
475  Subscriber subscribe(const std::string& topic, uint32_t queue_size,
476  void(T::*fp)(const boost::shared_ptr<M const>&) const, T* obj,
477  const TransportHints& transport_hints = TransportHints())
478  {
479  SubscribeOptions ops;
480  ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
481  ops.transport_hints = transport_hints;
482  return subscribe(ops);
483  }
484 
528  template<class M, class T>
529  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M),
530  const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
531  {
532  SubscribeOptions ops;
533  ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
534  ops.tracked_object = obj;
535  ops.transport_hints = transport_hints;
536  return subscribe(ops);
537  }
538 
539  template<class M, class T>
540  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const,
541  const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
542  {
543  SubscribeOptions ops;
544  ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
545  ops.tracked_object = obj;
546  ops.transport_hints = transport_hints;
547  return subscribe(ops);
548  }
549 
593  template<class M, class T>
594  Subscriber subscribe(const std::string& topic, uint32_t queue_size,
595  void(T::*fp)(const boost::shared_ptr<M const>&),
596  const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
597  {
598  SubscribeOptions ops;
599  ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
600  ops.tracked_object = obj;
601  ops.transport_hints = transport_hints;
602  return subscribe(ops);
603  }
604  template<class M, class T>
605  Subscriber subscribe(const std::string& topic, uint32_t queue_size,
606  void(T::*fp)(const boost::shared_ptr<M const>&) const,
607  const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
608  {
609  SubscribeOptions ops;
610  ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
611  ops.tracked_object = obj;
612  ops.transport_hints = transport_hints;
613  return subscribe(ops);
614  }
615 
655  template<class M>
656  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(M), const TransportHints& transport_hints = TransportHints())
657  {
658  SubscribeOptions ops;
659  ops.template initByFullCallbackType<M>(topic, queue_size, fp);
660  ops.transport_hints = transport_hints;
661  return subscribe(ops);
662  }
663 
703  template<class M>
704  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr<M const>&), const TransportHints& transport_hints = TransportHints())
705  {
706  SubscribeOptions ops;
707  ops.template init<M>(topic, queue_size, fp);
708  ops.transport_hints = transport_hints;
709  return subscribe(ops);
710  }
711 
749  template<class M>
750  Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
751  const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
752  {
753  SubscribeOptions ops;
754  ops.template init<M>(topic, queue_size, callback);
755  ops.tracked_object = tracked_object;
756  ops.transport_hints = transport_hints;
757  return subscribe(ops);
758  }
759 
798  template<class M, class C>
799  Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (C)>& callback,
800  const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
801  {
802  SubscribeOptions ops;
803  ops.template initByFullCallbackType<C>(topic, queue_size, callback);
804  ops.tracked_object = tracked_object;
805  ops.transport_hints = transport_hints;
806  return subscribe(ops);
807  }
808 
836  Subscriber subscribe(SubscribeOptions& ops);
837 
839  // Versions of advertiseService()
841 
878  template<class T, class MReq, class MRes>
879  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
880  {
882  ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj, _1, _2));
883  return advertiseService(ops);
884  }
885 
923  template<class T, class MReq, class MRes>
924  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), T *obj)
925  {
927  ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj, _1));
928  return advertiseService(ops);
929  }
930 
969  template<class T, class MReq, class MRes>
970  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr<T>& obj)
971  {
973  ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj.get(), _1, _2));
974  ops.tracked_object = obj;
975  return advertiseService(ops);
976  }
977 
1016  template<class T, class MReq, class MRes>
1017  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), const boost::shared_ptr<T>& obj)
1018  {
1020  ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj.get(), _1));
1021  ops.tracked_object = obj;
1022  return advertiseService(ops);
1023  }
1024 
1060  template<class MReq, class MRes>
1061  ServiceServer advertiseService(const std::string& service, bool(*srv_func)(MReq&, MRes&))
1062  {
1064  ops.template init<MReq, MRes>(service, srv_func);
1065  return advertiseService(ops);
1066  }
1067 
1103  template<class MReq, class MRes>
1104  ServiceServer advertiseService(const std::string& service, bool(*srv_func)(ServiceEvent<MReq, MRes>&))
1105  {
1107  ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
1108  return advertiseService(ops);
1109  }
1110 
1144  template<class MReq, class MRes>
1145  ServiceServer advertiseService(const std::string& service, const boost::function<bool(MReq&, MRes&)>& callback,
1146  const VoidConstPtr& tracked_object = VoidConstPtr())
1147  {
1149  ops.template init<MReq, MRes>(service, callback);
1150  ops.tracked_object = tracked_object;
1151  return advertiseService(ops);
1152  }
1153 
1189  template<class S>
1190  ServiceServer advertiseService(const std::string& service, const boost::function<bool(S&)>& callback,
1191  const VoidConstPtr& tracked_object = VoidConstPtr())
1192  {
1194  ops.template initBySpecType<S>(service, callback);
1195  ops.tracked_object = tracked_object;
1196  return advertiseService(ops);
1197  }
1198 
1222  ServiceServer advertiseService(AdvertiseServiceOptions& ops);
1223 
1225  // Versions of serviceClient()
1227 
1239  template<class MReq, class MRes>
1240  ServiceClient serviceClient(const std::string& service_name, bool persistent = false,
1241  const M_string& header_values = M_string())
1242  {
1244  ops.template init<MReq, MRes>(service_name, persistent, header_values);
1245  return serviceClient(ops);
1246  }
1247 
1259  template<class Service>
1260  ServiceClient serviceClient(const std::string& service_name, bool persistent = false,
1261  const M_string& header_values = M_string())
1262  {
1264  ops.template init<Service>(service_name, persistent, header_values);
1265  return serviceClient(ops);
1266  }
1267 
1275  ServiceClient serviceClient(ServiceClientOptions& ops);
1276 
1278  // Versions of createTimer()
1280 
1293  template<class Handler, class Obj>
1294  Timer createTimer(Rate r, Handler h, Obj o, bool oneshot = false, bool autostart = true) const
1295  {
1296  return createTimer(r.expectedCycleTime(), h, o, oneshot, autostart);
1297  }
1298 
1312  template<class T>
1313  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&) const, T* obj,
1314  bool oneshot = false, bool autostart = true) const
1315  {
1316  return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
1317  }
1318 
1332  template<class T>
1333  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), T* obj,
1334  bool oneshot = false, bool autostart = true) const
1335  {
1336  return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
1337  }
1338 
1354  template<class T>
1355  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), const boost::shared_ptr<T>& obj,
1356  bool oneshot = false, bool autostart = true) const
1357  {
1358  TimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
1359  ops.tracked_object = obj;
1360  ops.oneshot = oneshot;
1361  ops.autostart = autostart;
1362  return createTimer(ops);
1363  }
1364 
1377  Timer createTimer(Duration period, const TimerCallback& callback, bool oneshot = false,
1378  bool autostart = true) const;
1379 
1389  Timer createTimer(TimerOptions& ops) const;
1390 
1392  // Versions of createWallTimer()
1394 
1409  template<class T>
1410  WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), T* obj,
1411  bool oneshot = false, bool autostart = true) const
1412  {
1413  return createWallTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
1414  }
1415 
1431  template<class T>
1432  WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&),
1433  const boost::shared_ptr<T>& obj,
1434  bool oneshot = false, bool autostart = true) const
1435  {
1436  WallTimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
1437  ops.tracked_object = obj;
1438  ops.oneshot = oneshot;
1439  ops.autostart = autostart;
1440  return createWallTimer(ops);
1441  }
1442 
1455  WallTimer createWallTimer(WallDuration period, const WallTimerCallback& callback,
1456  bool oneshot = false, bool autostart = true) const;
1457 
1468  WallTimer createWallTimer(WallTimerOptions& ops) const;
1469 
1471  // Versions of createSteadyTimer()
1473 
1488  template<class T>
1489  SteadyTimer createSteadyTimer(WallDuration period, void(T::*callback)(const SteadyTimerEvent&), T* obj,
1490  bool oneshot = false, bool autostart = true) const
1491  {
1492  return createSteadyTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
1493  }
1494 
1510  template<class T>
1511  SteadyTimer createSteadyTimer(WallDuration period, void(T::*callback)(const SteadyTimerEvent&),
1512  const boost::shared_ptr<T>& obj,
1513  bool oneshot = false, bool autostart = true) const
1514  {
1515  SteadyTimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
1516  ops.tracked_object = obj;
1517  ops.oneshot = oneshot;
1518  ops.autostart = autostart;
1519  return createSteadyTimer(ops);
1520  }
1521 
1534  SteadyTimer createSteadyTimer(WallDuration period, const SteadyTimerCallback& callback,
1535  bool oneshot = false, bool autostart = true) const;
1536 
1547  SteadyTimer createSteadyTimer(SteadyTimerOptions& ops) const;
1548 
1555  void setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const;
1562  void setParam(const std::string& key, const std::string& s) const;
1569  void setParam(const std::string& key, const char* s) const;
1576  void setParam(const std::string& key, double d) const;
1583  void setParam(const std::string& key, int i) const;
1590  void setParam(const std::string& key, bool b) const;
1591 
1598  void setParam(const std::string& key, const std::vector<std::string>& vec) const;
1605  void setParam(const std::string& key, const std::vector<double>& vec) const;
1612  void setParam(const std::string& key, const std::vector<float>& vec) const;
1619  void setParam(const std::string& key, const std::vector<int>& vec) const;
1626  void setParam(const std::string& key, const std::vector<bool>& vec) const;
1627 
1634  void setParam(const std::string& key, const std::map<std::string, std::string>& map) const;
1641  void setParam(const std::string& key, const std::map<std::string, double>& map) const;
1648  void setParam(const std::string& key, const std::map<std::string, float>& map) const;
1655  void setParam(const std::string& key, const std::map<std::string, int>& map) const;
1662  void setParam(const std::string& key, const std::map<std::string, bool>& map) const;
1663 
1672  bool getParam(const std::string& key, std::string& s) const;
1683  bool getParam(const std::string& key, double& d) const;
1694  bool getParam(const std::string& key, float& f) const;
1705  bool getParam(const std::string& key, int& i) const;
1716  bool getParam(const std::string& key, bool& b) const;
1727  bool getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const;
1728 
1739  bool getParam(const std::string& key, std::vector<std::string>& vec) const;
1750  bool getParam(const std::string& key, std::vector<double>& vec) const;
1761  bool getParam(const std::string& key, std::vector<float>& vec) const;
1772  bool getParam(const std::string& key, std::vector<int>& vec) const;
1783  bool getParam(const std::string& key, std::vector<bool>& vec) const;
1784 
1795  bool getParam(const std::string& key, std::map<std::string, std::string>& map) const;
1806  bool getParam(const std::string& key, std::map<std::string, double>& map) const;
1817  bool getParam(const std::string& key, std::map<std::string, float>& map) const;
1828  bool getParam(const std::string& key, std::map<std::string, int>& map) const;
1839  bool getParam(const std::string& key, std::map<std::string, bool>& map) const;
1840 
1856  bool getParamCached(const std::string& key, std::string& s) const;
1870  bool getParamCached(const std::string& key, double& d) const;
1884  bool getParamCached(const std::string& key, float& f) const;
1898  bool getParamCached(const std::string& key, int& i) const;
1912  bool getParamCached(const std::string& key, bool& b) const;
1926  bool getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const;
1927 
1941  bool getParamCached(const std::string& key, std::vector<std::string>& vec) const;
1955  bool getParamCached(const std::string& key, std::vector<double>& vec) const;
1969  bool getParamCached(const std::string& key, std::vector<float>& vec) const;
1983  bool getParamCached(const std::string& key, std::vector<int>& vec) const;
1997  bool getParamCached(const std::string& key, std::vector<bool>& vec) const;
1998 
2012  bool getParamCached(const std::string& key, std::map<std::string, std::string>& map) const;
2026  bool getParamCached(const std::string& key, std::map<std::string, double>& map) const;
2040  bool getParamCached(const std::string& key, std::map<std::string, float>& map) const;
2054  bool getParamCached(const std::string& key, std::map<std::string, int>& map) const;
2068  bool getParamCached(const std::string& key, std::map<std::string, bool>& map) const;
2069 
2077  bool hasParam(const std::string& key) const;
2090  bool searchParam(const std::string& key, std::string& result) const;
2098  bool deleteParam(const std::string& key) const;
2099 
2104  bool getParamNames(std::vector<std::string>& keys) const;
2105 
2119  template<typename T>
2120  bool param(const std::string& param_name, T& param_val, const T& default_val) const
2121  {
2122  if (hasParam(param_name))
2123  {
2124  if (getParam(param_name, param_val))
2125  {
2126  return true;
2127  }
2128  }
2129 
2130  param_val = default_val;
2131  return false;
2132  }
2133 
2152  template<typename T>
2153  T param(const std::string& param_name, const T& default_val)
2154  {
2155  T param_val;
2156  param(param_name, param_val, default_val);
2157  return param_val;
2158  }
2159 
2166  void shutdown();
2167 
2175  bool ok() const;
2176 
2177 private:
2178  struct no_validate { };
2179  // this is pretty awful, but required to preserve public interface (and make minimum possible changes)
2180  std::string resolveName(const std::string& name, bool remap, no_validate) const;
2181 
2182  void construct(const std::string& ns, bool validate_name);
2183  void destruct();
2184 
2185  void initRemappings(const M_string& remappings);
2186 
2187  std::string remapName(const std::string& name) const;
2188 
2189  std::string namespace_;
2193 
2195 
2197 
2198  bool ok_;
2199 };
2200 
2201 }
2202 
2203 #endif // ROSCPP_NODE_HANDLE_H
d
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
const std::string & getUnresolvedNamespace() const
Returns the namespace associated with this NodeHandle as it was passed in (before it was resolved) ...
Definition: node_handle.h:197
ROSCPP_DECL bool getParamNames(std::vector< std::string > &keys)
Get the list of all the parameters in the server.
Definition: param.cpp:723
Timer createTimer(Duration period, void(T::*callback)(const TimerEvent &) const, T *obj, 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:1313
Manages an subscription callback on a specific topic.
Definition: subscriber.h:46
bool param(const std::string &param_name, T &param_val, const T &default_val)
Assign value from parameter server, with default.
Definition: param.h:608
Encapsulates all options available for creating a ServiceClient.
boost::shared_ptr< void const > VoidConstPtr
Definition: forwards.h:52
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Definition: forwards.h:94
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Definition: node_handle.h:540
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), T *obj)
Advertise a service, version for class member function with bare pointer using ros::ServiceEvent as t...
Definition: node_handle.h:924
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Definition: node_handle.h:605
f
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
Encapsulates all options available for starting a timer.
XmlRpcServer s
CallbackQueueInterface * callback_queue_
Definition: node_handle.h:2194
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for class member function with bare pointer.
Definition: node_handle.h:465
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this service from being called...
std::string unresolved_namespace_
Definition: node_handle.h:2190
bool latch
Whether or not this publication should "latch". A latching publication will automatically send out th...
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for class member function with shared_ptr.
Definition: node_handle.h:594
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &) const, T *obj, const TransportHints &transport_hints=TransportHints())
Definition: node_handle.h:475
VoidConstPtr tracked_object
Definition: timer_options.h:75
Abstract interface for a queue used to handle all callbacks within roscpp.
Encapsulates all options available for creating a Publisher.
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 service type.
Definition: node_handle.h:1260
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
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr< T > &obj)
Advertise a service, version for class member function with shared_ptr.
Definition: node_handle.h:970
ServiceServer advertiseService(const std::string &service, bool(*srv_func)(MReq &, MRes &))
Advertise a service, version for bare function.
Definition: node_handle.h:1061
ServiceServer advertiseService(const std::string &service, const boost::function< bool(MReq &, MRes &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
Advertise a service, version for arbitrary boost::function object.
Definition: node_handle.h:1145
Publisher advertise(const std::string &topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const VoidConstPtr &tracked_object=VoidConstPtr(), bool latch=false)
Advertise a topic, with most of the available options, including subscriber status callbacks...
Definition: node_handle.h:315
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
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
ServiceServer advertiseService(const std::string &service, const boost::function< bool(S &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
Advertise a service, version for arbitrary boost::function object using ros::ServiceEvent as the call...
Definition: node_handle.h:1190
std::map< std::string, std::string > M_string
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for arbitrary boost::function object.
Definition: node_handle.h:750
SteadyTimer createSteadyTimer(WallDuration period, void(T::*callback)(const SteadyTimerEvent &), const boost::shared_ptr< 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:1511
Timer createTimer(Duration period, void(T::*callback)(const TimerEvent &), const boost::shared_ptr< T > &obj, 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:1355
ROSCPP_DECL std::string remap(const std::string &name)
Apply remappings to a name.
Definition: names.cpp:123
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M) const, T *obj, const TransportHints &transport_hints=TransportHints())
and the const version
Definition: node_handle.h:413
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 ...
M_string unresolved_remappings_
Definition: node_handle.h:2192
Encapsulates all options available for creating a Subscriber.
Duration expectedCycleTime() const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Assign value from parameter server, with default.
Definition: node_handle.h:2120
roscpp&#39;s interface for creating subscribers, publishers, etc.
Definition: node_handle.h:87
boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
Definition: forwards.h:180
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(*fp)(M), const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for bare function.
Definition: node_handle.h:656
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
const std::string & getNamespace() const
Returns the namespace associated with this NodeHandle.
Definition: node_handle.h:191
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for class member function with shared_ptr.
Definition: node_handle.h:529
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
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Advertise a topic, simple version.
Definition: node_handle.h:249
Manages an advertisement on a specific topic.
Definition: publisher.h:47
TransportHints transport_hints
Hints for transport type and options.
Structure passed as a parameter to the callback invoked by a ros::SteadyTimer.
Definition: forwards.h:167
Event type for services, ros::ServiceEvent<MReq, MRes>& can be used in your callback instead of MReq&...
Manages a steady-clock timer callback.
Definition: steady_timer.h:46
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for arbitrary boost::function object.
Definition: node_handle.h:799
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< M const > &), const TransportHints &transport_hints=TransportHints())
Subscribe to a topic, version for bare function.
Definition: node_handle.h:704
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), const boost::shared_ptr< T > &obj)
Advertise a service, version for class member function with shared_ptr using ros::ServiceEvent as the...
Definition: node_handle.h:1017
boost::function< void(const WallTimerEvent &)> WallTimerCallback
Definition: forwards.h:162
Manages an service advertisement.
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this subscription.
ServiceServer advertiseService(const std::string &service, bool(*srv_func)(ServiceEvent< MReq, MRes > &))
Advertise a service, version for bare function using ros::ServiceEvent as the callback parameter type...
Definition: node_handle.h:1104
M_string remappings_
Definition: node_handle.h:2191
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
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), const boost::shared_ptr< 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:1432
Timer createTimer(Duration period, void(T::*callback)(const TimerEvent &), T *obj, 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:1333
CallbackQueueInterface * getCallbackQueue() const
Returns the callback queue associated with this NodeHandle. If none has been explicitly set...
Definition: node_handle.h:183
Structure passed as a parameter to the callback invoked by a ros::WallTimer.
Definition: forwards.h:149
Structure passed as a parameter to the callback invoked by a ros::Timer.
Definition: forwards.h:131
Manages a wall-clock timer callback.
Definition: wall_timer.h:46
NodeHandleBackingCollection * collection_
Definition: node_handle.h:2196
Encapsulates all options available for starting a timer.
T param(const std::string &param_name, const T &default_val)
Return value from parameter server, or default if unavailable.
Definition: node_handle.h:2153


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54