00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef ROSCPP_NODE_HANDLE_H
00029 #define ROSCPP_NODE_HANDLE_H
00030
00031 #include "ros/forwards.h"
00032 #include "ros/publisher.h"
00033 #include "ros/subscriber.h"
00034 #include "ros/service_server.h"
00035 #include "ros/service_client.h"
00036 #include "ros/timer.h"
00037 #include "ros/wall_timer.h"
00038 #include "ros/advertise_options.h"
00039 #include "ros/advertise_service_options.h"
00040 #include "ros/subscribe_options.h"
00041 #include "ros/service_client_options.h"
00042 #include "ros/timer_options.h"
00043 #include "ros/wall_timer_options.h"
00044 #include "ros/spinner.h"
00045 #include "ros/init.h"
00046
00047 #include <boost/bind.hpp>
00048
00049 #include <XmlRpcValue.h>
00050
00051 namespace ros
00052 {
00053
00054 class NodeHandleBackingCollection;
00055
00081 class NodeHandle
00082 {
00083 public:
00096 NodeHandle(const std::string& ns = std::string(), const M_string& remappings = M_string());
00103 NodeHandle(const NodeHandle& rhs);
00116 NodeHandle(const NodeHandle& parent, const std::string& ns);
00131 NodeHandle(const NodeHandle& parent, const std::string& ns, const M_string& remappings);
00137 ~NodeHandle();
00138
00139 NodeHandle& operator=(const NodeHandle& rhs);
00140
00148 void setCallbackQueue(CallbackQueueInterface* queue);
00149
00153 CallbackQueueInterface* getCallbackQueue() const { return callback_queue_ ? callback_queue_ : (CallbackQueueInterface*)getGlobalCallbackQueue(); }
00154
00158 const std::string& getNamespace() const { return namespace_; }
00159
00163 const std::string& getUnresolvedNamespace() const { return unresolved_namespace_; }
00164
00178 std::string resolveName(const std::string& name, bool remap = true) const;
00179
00181
00183
00202 template <class M>
00203 Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false)
00204 {
00205 AdvertiseOptions ops;
00206 ops.template init<M>(topic, queue_size);
00207 ops.latch = latch;
00208 return advertise(ops);
00209 }
00210
00261 template <class M>
00262 Publisher advertise(const std::string& topic, uint32_t queue_size,
00263 const SubscriberStatusCallback& connect_cb,
00264 const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
00265 const VoidConstPtr& tracked_object = VoidConstPtr(),
00266 bool latch = false)
00267 {
00268 AdvertiseOptions ops;
00269 ops.template init<M>(topic, queue_size, connect_cb, disconnect_cb);
00270 ops.tracked_object = tracked_object;
00271 ops.latch = latch;
00272 return advertise(ops);
00273 }
00274
00296 Publisher advertise(AdvertiseOptions& ops);
00297
00298
00300
00302
00340 template<class M, class T>
00341 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), T* obj, const TransportHints& transport_hints = TransportHints())
00342 {
00343 SubscribeOptions ops;
00344 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
00345 ops.transport_hints = transport_hints;
00346 return subscribe(ops);
00347 }
00348
00387 template<class M, class T>
00388 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())
00389 {
00390 SubscribeOptions ops;
00391 ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
00392 ops.transport_hints = transport_hints;
00393 return subscribe(ops);
00394 }
00395
00435 template<class M, class T>
00436 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())
00437 {
00438 SubscribeOptions ops;
00439 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00440 ops.tracked_object = obj;
00441 ops.transport_hints = transport_hints;
00442 return subscribe(ops);
00443 }
00444
00484 template<class M, class T>
00485 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())
00486 {
00487 SubscribeOptions ops;
00488 ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00489 ops.tracked_object = obj;
00490 ops.transport_hints = transport_hints;
00491 return subscribe(ops);
00492 }
00493
00530 template<class M>
00531 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(M), const TransportHints& transport_hints = TransportHints())
00532 {
00533 SubscribeOptions ops;
00534 ops.template initByFullCallbackType<M>(topic, queue_size, fp);
00535 ops.transport_hints = transport_hints;
00536 return subscribe(ops);
00537 }
00538
00575 template<class M>
00576 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr<M const>&), const TransportHints& transport_hints = TransportHints())
00577 {
00578 SubscribeOptions ops;
00579 ops.template init<M>(topic, queue_size, fp);
00580 ops.transport_hints = transport_hints;
00581 return subscribe(ops);
00582 }
00583
00618 template<class M>
00619 Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
00620 const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
00621 {
00622 SubscribeOptions ops;
00623 ops.template init<M>(topic, queue_size, callback);
00624 ops.tracked_object = tracked_object;
00625 ops.transport_hints = transport_hints;
00626 return subscribe(ops);
00627 }
00628
00664 template<class M, class C>
00665 Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (C)>& callback,
00666 const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
00667 {
00668 SubscribeOptions ops;
00669 ops.template initByFullCallbackType<C>(topic, queue_size, callback);
00670 ops.tracked_object = tracked_object;
00671 ops.transport_hints = transport_hints;
00672 return subscribe(ops);
00673 }
00674
00698 Subscriber subscribe(SubscribeOptions& ops);
00699
00701
00703
00733 template<class T, class MReq, class MRes>
00734 ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
00735 {
00736 AdvertiseServiceOptions ops;
00737 ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj, _1, _2));
00738 return advertiseService(ops);
00739 }
00740
00771 template<class T, class MReq, class MRes>
00772 ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), T *obj)
00773 {
00774 AdvertiseServiceOptions ops;
00775 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj, _1));
00776 return advertiseService(ops);
00777 }
00778
00810 template<class T, class MReq, class MRes>
00811 ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr<T>& obj)
00812 {
00813 AdvertiseServiceOptions ops;
00814 ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj.get(), _1, _2));
00815 ops.tracked_object = obj;
00816 return advertiseService(ops);
00817 }
00818
00850 template<class T, class MReq, class MRes>
00851 ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), const boost::shared_ptr<T>& obj)
00852 {
00853 AdvertiseServiceOptions ops;
00854 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj.get(), _1));
00855 ops.tracked_object = obj;
00856 return advertiseService(ops);
00857 }
00858
00887 template<class MReq, class MRes>
00888 ServiceServer advertiseService(const std::string& service, bool(*srv_func)(MReq&, MRes&))
00889 {
00890 AdvertiseServiceOptions ops;
00891 ops.template init<MReq, MRes>(service, srv_func);
00892 return advertiseService(ops);
00893 }
00894
00923 template<class MReq, class MRes>
00924 ServiceServer advertiseService(const std::string& service, bool(*srv_func)(ServiceEvent<MReq, MRes>&))
00925 {
00926 AdvertiseServiceOptions ops;
00927 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
00928 return advertiseService(ops);
00929 }
00930
00957 template<class MReq, class MRes>
00958 ServiceServer advertiseService(const std::string& service, const boost::function<bool(MReq&, MRes&)>& callback, const VoidConstPtr& tracked_object = VoidConstPtr())
00959 {
00960 AdvertiseServiceOptions ops;
00961 ops.template init<MReq, MRes>(service, callback);
00962 ops.tracked_object = tracked_object;
00963 return advertiseService(ops);
00964 }
00965
00994 template<class S>
00995 ServiceServer advertiseService(const std::string& service, const boost::function<bool(S&)>& callback, const VoidConstPtr& tracked_object = VoidConstPtr())
00996 {
00997 AdvertiseServiceOptions ops;
00998 ops.template initBySpecType<S>(service, callback);
00999 ops.tracked_object = tracked_object;
01000 return advertiseService(ops);
01001 }
01002
01022 ServiceServer advertiseService(AdvertiseServiceOptions& ops);
01023
01025
01027
01039 template<class MReq, class MRes>
01040 ServiceClient serviceClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
01041 {
01042 ServiceClientOptions ops;
01043 ops.template init<MReq, MRes>(service_name, persistent, header_values);
01044 return serviceClient(ops);
01045 }
01046
01058 template<class Service>
01059 ServiceClient serviceClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
01060 {
01061 ServiceClientOptions ops;
01062 ops.template init<Service>(service_name, persistent, header_values);
01063 return serviceClient(ops);
01064 }
01065
01073 ServiceClient serviceClient(ServiceClientOptions& ops);
01074
01076
01078
01090 template<class T>
01091 Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&) const, T* obj, bool oneshot = false) const
01092 {
01093 return createTimer(period, boost::bind(callback, obj, _1), oneshot);
01094 }
01095
01108 template<class T>
01109 Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), T* obj, bool oneshot = false) const
01110 {
01111 return createTimer(period, boost::bind(callback, obj, _1), oneshot);
01112 }
01113
01128 template<class T>
01129 Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), const boost::shared_ptr<T>& obj, bool oneshot = false) const
01130 {
01131 TimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
01132 ops.tracked_object = obj;
01133 ops.oneshot = oneshot;
01134 return createTimer(ops);
01135 }
01136
01148 Timer createTimer(Duration period, const TimerCallback& callback, bool oneshot = false) const;
01149
01159 Timer createTimer(TimerOptions& ops) const;
01160
01162
01164
01178 template<class T>
01179 WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), T* obj, bool oneshot = false) const
01180 {
01181 return createWallTimer(period, boost::bind(callback, obj, _1), oneshot);
01182 }
01183
01199 template<class T>
01200 WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), const boost::shared_ptr<T>& obj, bool oneshot = false) const
01201 {
01202 WallTimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
01203 ops.tracked_object = obj;
01204 ops.oneshot = oneshot;
01205 return createWallTimer(ops);
01206 }
01207
01220 WallTimer createWallTimer(WallDuration period, const WallTimerCallback& callback, bool oneshot = false) const;
01221
01232 WallTimer createWallTimer(WallTimerOptions& ops) const;
01233
01240 void setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const;
01247 void setParam(const std::string& key, const std::string& s) const;
01254 void setParam(const std::string& key, const char* s) const;
01261 void setParam(const std::string& key, double d) const;
01268 void setParam(const std::string& key, int i) const;
01275 void setParam(const std::string& key, bool b) const;
01276
01285 bool getParam(const std::string& key, std::string& s) const;
01294 bool getParam(const std::string& key, double& d) const;
01303 bool getParam(const std::string& key, int& i) const;
01312 bool getParam(const std::string& key, bool& b) const;
01321 bool getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const;
01322
01336 bool getParamCached(const std::string& key, std::string& s) const;
01350 bool getParamCached(const std::string& key, double& d) const;
01364 bool getParamCached(const std::string& key, int& i) const;
01378 bool getParamCached(const std::string& key, bool& b) const;
01392 bool getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const;
01393
01401 bool hasParam(const std::string& key) const;
01414 bool searchParam(const std::string& key, std::string& result) const;
01422 bool deleteParam(const std::string& key) const;
01423
01436 template<typename T>
01437 void param(const std::string& param_name, T& param_val, const T& default_val) const
01438 {
01439 if (hasParam(param_name))
01440 {
01441 if (getParam(param_name, param_val))
01442 {
01443 return;
01444 }
01445 }
01446
01447 param_val = default_val;
01448 }
01449
01456 void shutdown();
01457
01465 bool ok() const;
01466
01467 private:
01468 struct no_validate { };
01469
01470 std::string resolveName(const std::string& name, bool remap, no_validate) const;
01471
01472 void construct(const std::string& ns, bool validate_name);
01473 void destruct();
01474
01475 void initRemappings(const M_string& remappings);
01476
01477 std::string remapName(const std::string& name) const;
01478
01479 std::string namespace_;
01480 std::string unresolved_namespace_;
01481 M_string remappings_;
01482 M_string unresolved_remappings_;
01483
01484 CallbackQueueInterface* callback_queue_;
01485
01486 NodeHandleBackingCollection* collection_;
01487
01488 bool ok_;
01489 };
01490
01491 }
01492
01493 #endif // ROSCPP_NODE_HANDLE_H