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 <xmlrpcpp/XmlRpcValue.h>
51 
52 namespace ros
53 {
54 
55  class NodeHandleBackingCollection;
56 
85  class ROSCPP_DECL NodeHandle
86  {
87  public:
102  NodeHandle(const std::string& ns = std::string(), const M_string& remappings = M_string());
110  NodeHandle(const NodeHandle& rhs);
132  NodeHandle(const NodeHandle& parent, const std::string& ns);
154  NodeHandle(const NodeHandle& parent, const std::string& ns, const M_string& remappings);
162  ~NodeHandle();
163 
164  NodeHandle& operator=(const NodeHandle& rhs);
165 
174  void setCallbackQueue(CallbackQueueInterface* queue);
175 
182  {
183  return callback_queue_ ? callback_queue_ : (CallbackQueueInterface*)getGlobalCallbackQueue();
184  }
185 
189  const std::string& getNamespace() const { return namespace_; }
190 
195  const std::string& getUnresolvedNamespace() const { return unresolved_namespace_; }
196 
213  std::string resolveName(const std::string& name, bool remap = true) const;
214 
216  // Versions of advertise()
218 
246  template <class M>
247  Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false)
248  {
249  AdvertiseOptions ops;
250  ops.template init<M>(topic, queue_size);
251  ops.latch = latch;
252  return advertise(ops);
253  }
254 
312  template <class M>
313  Publisher advertise(const std::string& topic, uint32_t queue_size,
314  const SubscriberStatusCallback& connect_cb,
315  const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
316  const VoidConstPtr& tracked_object = VoidConstPtr(),
317  bool latch = false)
318  {
319  AdvertiseOptions ops;
320  ops.template init<M>(topic, queue_size, connect_cb, disconnect_cb);
321  ops.tracked_object = tracked_object;
322  ops.latch = latch;
323  return advertise(ops);
324  }
325 
351  Publisher advertise(AdvertiseOptions& ops);
352 
353 
355  // Versions of subscribe()
357 
399  template<class M, class T>
400  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), T* obj,
401  const TransportHints& transport_hints = TransportHints())
402  {
403  SubscribeOptions ops;
404  ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1));
405  ops.transport_hints = transport_hints;
406  return subscribe(ops);
407  }
408 
410  template<class M, class T>
411  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const, T* obj,
412  const TransportHints& transport_hints = TransportHints())
413  {
414  SubscribeOptions ops;
415  ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1));
416  ops.transport_hints = transport_hints;
417  return subscribe(ops);
418  }
419 
462  template<class M, class T>
463  Subscriber subscribe(const std::string& topic, uint32_t queue_size,
464  void(T::*fp)(const boost::shared_ptr<M const>&), T* obj,
465  const TransportHints& transport_hints = TransportHints())
466  {
467  SubscribeOptions ops;
468  ops.template init<M>(topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1));
469  ops.transport_hints = transport_hints;
470  return subscribe(ops);
471  }
472  template<class M, class T>
473  Subscriber subscribe(const std::string& topic, uint32_t queue_size,
474  void(T::*fp)(const boost::shared_ptr<M const>&) const, T* obj,
475  const TransportHints& transport_hints = TransportHints())
476  {
477  SubscribeOptions ops;
478  ops.template init<M>(topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1));
479  ops.transport_hints = transport_hints;
480  return subscribe(ops);
481  }
482 
526  template<class M, class T>
527  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M),
528  const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
529  {
530  SubscribeOptions ops;
531  ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1));
532  ops.tracked_object = obj;
533  ops.transport_hints = transport_hints;
534  return subscribe(ops);
535  }
536 
537  template<class M, class T>
538  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const,
539  const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
540  {
541  SubscribeOptions ops;
542  ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1));
543  ops.tracked_object = obj;
544  ops.transport_hints = transport_hints;
545  return subscribe(ops);
546  }
547 
591  template<class M, class T>
592  Subscriber subscribe(const std::string& topic, uint32_t queue_size,
593  void(T::*fp)(const boost::shared_ptr<M const>&),
594  const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
595  {
596  SubscribeOptions ops;
597  ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1));
598  ops.tracked_object = obj;
599  ops.transport_hints = transport_hints;
600  return subscribe(ops);
601  }
602  template<class M, class T>
603  Subscriber subscribe(const std::string& topic, uint32_t queue_size,
604  void(T::*fp)(const boost::shared_ptr<M const>&) const,
605  const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
606  {
607  SubscribeOptions ops;
608  ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1));
609  ops.tracked_object = obj;
610  ops.transport_hints = transport_hints;
611  return subscribe(ops);
612  }
613 
653  template<class M>
654  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(M), const TransportHints& transport_hints = TransportHints())
655  {
656  SubscribeOptions ops;
657  ops.template initByFullCallbackType<M>(topic, queue_size, fp);
658  ops.transport_hints = transport_hints;
659  return subscribe(ops);
660  }
661 
701  template<class M>
702  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr<M const>&), const TransportHints& transport_hints = TransportHints())
703  {
704  SubscribeOptions ops;
705  ops.template init<M>(topic, queue_size, fp);
706  ops.transport_hints = transport_hints;
707  return subscribe(ops);
708  }
709 
747  template<class M>
748  Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
749  const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
750  {
751  SubscribeOptions ops;
752  ops.template init<M>(topic, queue_size, callback);
753  ops.tracked_object = tracked_object;
754  ops.transport_hints = transport_hints;
755  return subscribe(ops);
756  }
757 
796  template<class M, class C>
797  Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (C)>& callback,
798  const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
799  {
800  SubscribeOptions ops;
801  ops.template initByFullCallbackType<C>(topic, queue_size, callback);
802  ops.tracked_object = tracked_object;
803  ops.transport_hints = transport_hints;
804  return subscribe(ops);
805  }
806 
834  Subscriber subscribe(SubscribeOptions& ops);
835 
837  // Versions of advertiseService()
839 
876  template<class T, class MReq, class MRes>
877  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
878  {
880  ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj, boost::placeholders::_1, boost::placeholders::_2));
881  return advertiseService(ops);
882  }
883 
921  template<class T, class MReq, class MRes>
922  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), T *obj)
923  {
925  ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj, boost::placeholders::_1));
926  return advertiseService(ops);
927  }
928 
967  template<class T, class MReq, class MRes>
968  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr<T>& obj)
969  {
971  ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj.get(), boost::placeholders::_1, boost::placeholders::_2));
972  ops.tracked_object = obj;
973  return advertiseService(ops);
974  }
975 
1014  template<class T, class MReq, class MRes>
1015  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), const boost::shared_ptr<T>& obj)
1016  {
1018  ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj.get(), boost::placeholders::_1));
1019  ops.tracked_object = obj;
1020  return advertiseService(ops);
1021  }
1022 
1058  template<class MReq, class MRes>
1059  ServiceServer advertiseService(const std::string& service, bool(*srv_func)(MReq&, MRes&))
1060  {
1062  ops.template init<MReq, MRes>(service, srv_func);
1063  return advertiseService(ops);
1064  }
1065 
1101  template<class MReq, class MRes>
1102  ServiceServer advertiseService(const std::string& service, bool(*srv_func)(ServiceEvent<MReq, MRes>&))
1103  {
1105  ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
1106  return advertiseService(ops);
1107  }
1108 
1142  template<class MReq, class MRes>
1143  ServiceServer advertiseService(const std::string& service, const boost::function<bool(MReq&, MRes&)>& callback,
1144  const VoidConstPtr& tracked_object = VoidConstPtr())
1145  {
1147  ops.template init<MReq, MRes>(service, callback);
1148  ops.tracked_object = tracked_object;
1149  return advertiseService(ops);
1150  }
1151 
1187  template<class S>
1188  ServiceServer advertiseService(const std::string& service, const boost::function<bool(S&)>& callback,
1189  const VoidConstPtr& tracked_object = VoidConstPtr())
1190  {
1192  ops.template initBySpecType<S>(service, callback);
1193  ops.tracked_object = tracked_object;
1194  return advertiseService(ops);
1195  }
1196 
1220  ServiceServer advertiseService(AdvertiseServiceOptions& ops);
1221 
1223  // Versions of serviceClient()
1225 
1237  template<class MReq, class MRes>
1238  ServiceClient serviceClient(const std::string& service_name, bool persistent = false,
1239  const M_string& header_values = M_string())
1240  {
1242  ops.template init<MReq, MRes>(service_name, persistent, header_values);
1243  return serviceClient(ops);
1244  }
1245 
1257  template<class Service>
1258  ServiceClient serviceClient(const std::string& service_name, bool persistent = false,
1259  const M_string& header_values = M_string())
1260  {
1262  ops.template init<Service>(service_name, persistent, header_values);
1263  return serviceClient(ops);
1264  }
1265 
1273  ServiceClient serviceClient(ServiceClientOptions& ops);
1274 
1276  // Versions of createTimer()
1278 
1291  template<class Handler, class Obj>
1292  Timer createTimer(Rate r, Handler h, Obj o, bool oneshot = false, bool autostart = true) const
1293  {
1294  return createTimer(r.expectedCycleTime(), h, o, oneshot, autostart);
1295  }
1296 
1310  template<class T>
1311  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&) const, T* obj,
1312  bool oneshot = false, bool autostart = true) const
1313  {
1314  return createTimer(period, boost::bind(callback, obj, boost::placeholders::_1), oneshot, autostart);
1315  }
1316 
1330  template<class T>
1331  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), T* obj,
1332  bool oneshot = false, bool autostart = true) const
1333  {
1334  return createTimer(period, boost::bind(callback, obj, boost::placeholders::_1), oneshot, autostart);
1335  }
1336 
1352  template<class T>
1353  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), const boost::shared_ptr<T>& obj,
1354  bool oneshot = false, bool autostart = true) const
1355  {
1356  TimerOptions ops(period, boost::bind(callback, obj.get(), boost::placeholders::_1), 0);
1357  ops.tracked_object = obj;
1358  ops.oneshot = oneshot;
1359  ops.autostart = autostart;
1360  return createTimer(ops);
1361  }
1362 
1375  Timer createTimer(Duration period, const TimerCallback& callback, bool oneshot = false,
1376  bool autostart = true) const;
1377 
1387  Timer createTimer(TimerOptions& ops) const;
1388 
1390  // Versions of createWallTimer()
1392 
1407  template<class T>
1408  WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), T* obj,
1409  bool oneshot = false, bool autostart = true) const
1410  {
1411  return createWallTimer(period, boost::bind(callback, obj, boost::placeholders::_1), oneshot, autostart);
1412  }
1413 
1429  template<class T>
1430  WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&),
1431  const boost::shared_ptr<T>& obj,
1432  bool oneshot = false, bool autostart = true) const
1433  {
1434  WallTimerOptions ops(period, boost::bind(callback, obj.get(), boost::placeholders::_1), 0);
1435  ops.tracked_object = obj;
1436  ops.oneshot = oneshot;
1437  ops.autostart = autostart;
1438  return createWallTimer(ops);
1439  }
1440 
1453  WallTimer createWallTimer(WallDuration period, const WallTimerCallback& callback,
1454  bool oneshot = false, bool autostart = true) const;
1455 
1466  WallTimer createWallTimer(WallTimerOptions& ops) const;
1467 
1469  // Versions of createSteadyTimer()
1471 
1486  template<class T>
1487  SteadyTimer createSteadyTimer(WallDuration period, void(T::*callback)(const SteadyTimerEvent&), T* obj,
1488  bool oneshot = false, bool autostart = true) const
1489  {
1490  return createSteadyTimer(period, boost::bind(callback, obj, boost::placeholders::_1), oneshot, autostart);
1491  }
1492 
1508  template<class T>
1509  SteadyTimer createSteadyTimer(WallDuration period, void(T::*callback)(const SteadyTimerEvent&),
1510  const boost::shared_ptr<T>& obj,
1511  bool oneshot = false, bool autostart = true) const
1512  {
1513  SteadyTimerOptions ops(period, boost::bind(callback, obj.get(), boost::placeholders::_1), 0);
1514  ops.tracked_object = obj;
1515  ops.oneshot = oneshot;
1516  ops.autostart = autostart;
1517  return createSteadyTimer(ops);
1518  }
1519 
1532  SteadyTimer createSteadyTimer(WallDuration period, const SteadyTimerCallback& callback,
1533  bool oneshot = false, bool autostart = true) const;
1534 
1545  SteadyTimer createSteadyTimer(SteadyTimerOptions& ops) const;
1546 
1553  void setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const;
1560  void setParam(const std::string& key, const std::string& s) const;
1567  void setParam(const std::string& key, const char* s) const;
1574  void setParam(const std::string& key, double d) const;
1581  void setParam(const std::string& key, int i) const;
1588  void setParam(const std::string& key, bool b) const;
1589 
1596  void setParam(const std::string& key, const std::vector<std::string>& vec) const;
1603  void setParam(const std::string& key, const std::vector<double>& vec) const;
1610  void setParam(const std::string& key, const std::vector<float>& vec) const;
1617  void setParam(const std::string& key, const std::vector<int>& vec) const;
1624  void setParam(const std::string& key, const std::vector<bool>& vec) const;
1625 
1632  void setParam(const std::string& key, const std::map<std::string, std::string>& map) const;
1639  void setParam(const std::string& key, const std::map<std::string, double>& map) const;
1646  void setParam(const std::string& key, const std::map<std::string, float>& map) const;
1653  void setParam(const std::string& key, const std::map<std::string, int>& map) const;
1660  void setParam(const std::string& key, const std::map<std::string, bool>& map) const;
1661 
1670  bool getParam(const std::string& key, std::string& s) const;
1681  bool getParam(const std::string& key, double& d) const;
1692  bool getParam(const std::string& key, float& f) const;
1703  bool getParam(const std::string& key, int& i) const;
1714  bool getParam(const std::string& key, bool& b) const;
1725  bool getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const;
1726 
1737  bool getParam(const std::string& key, std::vector<std::string>& vec) const;
1748  bool getParam(const std::string& key, std::vector<double>& vec) const;
1759  bool getParam(const std::string& key, std::vector<float>& vec) const;
1770  bool getParam(const std::string& key, std::vector<int>& vec) const;
1781  bool getParam(const std::string& key, std::vector<bool>& vec) const;
1782 
1793  bool getParam(const std::string& key, std::map<std::string, std::string>& map) const;
1804  bool getParam(const std::string& key, std::map<std::string, double>& map) const;
1815  bool getParam(const std::string& key, std::map<std::string, float>& map) const;
1826  bool getParam(const std::string& key, std::map<std::string, int>& map) const;
1837  bool getParam(const std::string& key, std::map<std::string, bool>& map) const;
1838 
1854  bool getParamCached(const std::string& key, std::string& s) const;
1868  bool getParamCached(const std::string& key, double& d) const;
1882  bool getParamCached(const std::string& key, float& f) const;
1896  bool getParamCached(const std::string& key, int& i) const;
1910  bool getParamCached(const std::string& key, bool& b) const;
1924  bool getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const;
1925 
1939  bool getParamCached(const std::string& key, std::vector<std::string>& vec) const;
1953  bool getParamCached(const std::string& key, std::vector<double>& vec) const;
1967  bool getParamCached(const std::string& key, std::vector<float>& vec) const;
1981  bool getParamCached(const std::string& key, std::vector<int>& vec) const;
1995  bool getParamCached(const std::string& key, std::vector<bool>& vec) const;
1996 
2010  bool getParamCached(const std::string& key, std::map<std::string, std::string>& map) const;
2024  bool getParamCached(const std::string& key, std::map<std::string, double>& map) const;
2038  bool getParamCached(const std::string& key, std::map<std::string, float>& map) const;
2052  bool getParamCached(const std::string& key, std::map<std::string, int>& map) const;
2066  bool getParamCached(const std::string& key, std::map<std::string, bool>& map) const;
2067 
2075  bool hasParam(const std::string& key) const;
2088  bool searchParam(const std::string& key, std::string& result) const;
2096  bool deleteParam(const std::string& key) const;
2097 
2102  bool getParamNames(std::vector<std::string>& keys) const;
2103 
2117  template<typename T>
2118  bool param(const std::string& param_name, T& param_val, const T& default_val) const
2119  {
2120  if (hasParam(param_name))
2121  {
2122  if (getParam(param_name, param_val))
2123  {
2124  return true;
2125  }
2126  }
2127 
2128  param_val = default_val;
2129  return false;
2130  }
2131 
2150  template<typename T>
2151  T param(const std::string& param_name, const T& default_val) const
2152  {
2153  T param_val;
2154  param(param_name, param_val, default_val);
2155  return param_val;
2156  }
2157 
2164  void shutdown();
2165 
2173  bool ok() const;
2174 
2175 private:
2176  struct no_validate { };
2177  // this is pretty awful, but required to preserve public interface (and make minimum possible changes)
2178  std::string resolveName(const std::string& name, bool remap, no_validate) const;
2179 
2180  void construct(const std::string& ns, bool validate_name);
2181  void destruct();
2182 
2183  void initRemappings(const M_string& remappings);
2184 
2185  std::string remapName(const std::string& name) const;
2186 
2187  std::string namespace_;
2191 
2193 
2195 
2196  bool ok_;
2197 };
2198 
2199 }
2200 
2201 #endif // ROSCPP_NODE_HANDLE_H
ros::NodeHandle::subscribe
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:538
service_client_options.h
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:1487
service_server.h
ros::Rate::expectedCycleTime
Duration expectedCycleTime() const
ros::NodeHandle::subscribe
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())
Definition: node_handle.h:463
ros::NodeHandle::namespace_
std::string namespace_
Definition: node_handle.h:2187
ros::TimerCallback
boost::function< void(const TimerEvent &)> TimerCallback
Definition: forwards.h:147
boost::shared_ptr< void const >
ros::TimerOptions
Encapsulates all options available for starting a timer.
Definition: timer_options.h:40
forwards.h
ros::param::param
bool param(const std::string &param_name, T &param_val, const T &default_val)
Assign value from parameter server, with default.
Definition: param.h:619
ros::NodeHandle::createTimer
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:1311
ros
ros::NodeHandle::getUnresolvedNamespace
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:195
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
Definition: node_handle.h:877
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), T *obj)
Definition: node_handle.h:922
ros::SteadyTimerOptions::autostart
bool autostart
Definition: steady_timer_options.h:79
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 service type.
Definition: node_handle.h:1258
ros::SubscribeOptions::transport_hints
TransportHints transport_hints
Hints for transport type and options.
Definition: subscribe_options.h:141
ros::AdvertiseServiceOptions::tracked_object
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this service from being called.
Definition: advertise_service_options.h:138
spinner.h
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:1238
ros::NodeHandle::createTimer
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:1353
wall_timer.h
ros::TransportHints
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
Definition: transport_hints.h:54
ros::SteadyTimerOptions::oneshot
bool oneshot
Definition: steady_timer_options.h:78
ros::NodeHandle::param
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:2118
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:608
ros::NodeHandle::advertise
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)
Definition: node_handle.h:313
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:1408
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, const boost::function< bool(S &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
Definition: node_handle.h:1188
ros::NodeHandleBackingCollection
Definition: node_handle.cpp:58
subscriber.h
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Definition: forwards.h:94
ros::NodeHandle::subscribe
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())
Definition: node_handle.h:748
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:400
ros::SubscribeOptions::tracked_object
VoidConstPtr tracked_object
An object whose destruction will prevent the callback associated with this subscription.
Definition: subscribe_options.h:139
timer_options.h
advertise_options.h
ros::WallTimerCallback
boost::function< void(const WallTimerEvent &)> WallTimerCallback
Definition: forwards.h:167
ros::NodeHandle::unresolved_namespace_
std::string unresolved_namespace_
Definition: node_handle.h:2188
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:603
ros::WallTimerOptions::tracked_object
VoidConstPtr tracked_object
Definition: wall_timer_options.h:76
ros::NodeHandle::subscribe
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:411
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(*fp)(M), const TransportHints &transport_hints=TransportHints())
Definition: node_handle.h:654
ros::NodeHandle::createWallTimer
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:1430
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr< T > &obj)
Definition: node_handle.h:968
ros::TimerOptions::autostart
bool autostart
Definition: timer_options.h:78
ros::Timer
Manages a timer callback.
Definition: timer.h:46
ros::WallTimer
Manages a wall-clock timer callback.
Definition: wall_timer.h:46
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:2192
service_client.h
advertise_service_options.h
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, const boost::function< bool(MReq &, MRes &)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr())
Definition: node_handle.h:1143
ros::TimerOptions::tracked_object
VoidConstPtr tracked_object
Definition: timer_options.h:75
init.h
ros::SteadyTimerOptions::tracked_object
VoidConstPtr tracked_object
Definition: steady_timer_options.h:76
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
ros::VoidConstPtr
boost::shared_ptr< void const > VoidConstPtr
Definition: forwards.h:52
timer.h
ros::NodeHandle::unresolved_remappings_
M_string unresolved_remappings_
Definition: node_handle.h:2190
ros::ServiceClientOptions
Encapsulates all options available for creating a ServiceClient.
Definition: service_client_options.h:41
subscribe_options.h
wall_timer_options.h
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, bool(*srv_func)(MReq &, MRes &))
Definition: node_handle.h:1059
ros::NodeHandle::createTimer
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:1331
ros::ServiceClient
Provides a handle-based interface to service client connections.
Definition: service_client.h:42
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr< M const > &), const TransportHints &transport_hints=TransportHints())
Definition: node_handle.h:702
ros::NodeHandle::getCallbackQueue
CallbackQueueInterface * getCallbackQueue() const
Returns the callback queue associated with this NodeHandle. If none has been explicitly set,...
Definition: node_handle.h:181
ros::SteadyTimerEvent
Structure passed as a parameter to the callback invoked by a ros::SteadyTimer.
Definition: forwards.h:172
XmlRpcValue.h
ros::NodeHandle::subscribe
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:603
ros::NodeHandle::subscribe
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())
Definition: node_handle.h:797
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:85
ros::TimerEvent
Structure passed as a parameter to the callback invoked by a ros::Timer.
Definition: forwards.h:132
publisher.h
ros::names::remap
ROSCPP_DECL std::string remap(const std::string &name)
Apply remappings to a name.
Definition: names.cpp:123
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(ServiceEvent< MReq, MRes > &), const boost::shared_ptr< T > &obj)
Definition: node_handle.h:1015
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:247
ros::Publisher
Manages an advertisement on a specific topic.
Definition: publisher.h:51
ros::SteadyTimerCallback
boost::function< void(const SteadyTimerEvent &)> SteadyTimerCallback
Definition: forwards.h:187
ros::WallTimerEvent
Structure passed as a parameter to the callback invoked by a ros::WallTimer.
Definition: forwards.h:152
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::subscribe
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())
Definition: node_handle.h:527
ros::NodeHandle::subscribe
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:473
ros::NodeHandle::createSteadyTimer
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:1509
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
Return value from parameter server, or default if unavailable.
Definition: node_handle.h:2151
ros::SteadyTimerOptions
Encapsulates all options available for starting a timer.
Definition: steady_timer_options.h:40
ros::WallTimerOptions::oneshot
bool oneshot
Definition: wall_timer_options.h:78
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::Rate
ros::ServiceServer
Manages an service advertisement.
Definition: service_server.h:45
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
Returns the namespace associated with this NodeHandle.
Definition: node_handle.h:189
ros::NodeHandle::remappings_
M_string remappings_
Definition: node_handle.h:2189
ros::WallDuration
ros::Subscriber
Manages an subscription callback on a specific topic.
Definition: subscriber.h:46
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::NodeHandle::subscribe
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())
Definition: node_handle.h:592
ros::Duration
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::NodeHandle::collection_
NodeHandleBackingCollection * collection_
Definition: node_handle.h:2194
ros::NodeHandle::no_validate
Definition: node_handle.h:2176
ros::NodeHandle::advertiseService
ServiceServer advertiseService(const std::string &service, bool(*srv_func)(ServiceEvent< MReq, MRes > &))
Definition: node_handle.h:1102
ros::ServiceEvent
Event type for services, ros::ServiceEvent<MReq, MRes>& can be used in your callback instead of MReq&...
Definition: service_callback_helper.h:70
ros::NodeHandle::ok_
bool ok_
Definition: node_handle.h:2196
ros::getGlobalCallbackQueue
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
Returns a pointer to the global default callback queue.
Definition: init.cpp:598
ros::M_string
std::map< std::string, std::string > M_string
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:1292


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas , Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:35