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/rate.h"
00038 #include "ros/wall_timer.h"
00039 #include "ros/advertise_options.h"
00040 #include "ros/advertise_service_options.h"
00041 #include "ros/subscribe_options.h"
00042 #include "ros/service_client_options.h"
00043 #include "ros/timer_options.h"
00044 #include "ros/wall_timer_options.h"
00045 #include "ros/spinner.h"
00046 #include "ros/init.h"
00047 #include "common.h"
00048
00049 #include <boost/bind.hpp>
00050
00051 #include <XmlRpcValue.h>
00052
00053 namespace ros
00054 {
00055
00056 class NodeHandleBackingCollection;
00057
00086 class ROSCPP_DECL NodeHandle
00087 {
00088 public:
00103 NodeHandle(const std::string& ns = std::string(), const M_string& remappings = M_string());
00111 NodeHandle(const NodeHandle& rhs);
00127 NodeHandle(const NodeHandle& parent, const std::string& ns);
00143 NodeHandle(const NodeHandle& parent, const std::string& ns, const M_string& remappings);
00151 ~NodeHandle();
00152
00153 NodeHandle& operator=(const NodeHandle& rhs);
00154
00163 void setCallbackQueue(CallbackQueueInterface* queue);
00164
00170 CallbackQueueInterface* getCallbackQueue() const
00171 {
00172 return callback_queue_ ? callback_queue_ : (CallbackQueueInterface*)getGlobalCallbackQueue();
00173 }
00174
00178 const std::string& getNamespace() const { return namespace_; }
00179
00184 const std::string& getUnresolvedNamespace() const { return unresolved_namespace_; }
00185
00202 std::string resolveName(const std::string& name, bool remap = true) const;
00203
00205
00207
00235 template <class M>
00236 Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false)
00237 {
00238 AdvertiseOptions ops;
00239 ops.template init<M>(topic, queue_size);
00240 ops.latch = latch;
00241 return advertise(ops);
00242 }
00243
00299 template <class M>
00300 Publisher advertise(const std::string& topic, uint32_t queue_size,
00301 const SubscriberStatusCallback& connect_cb,
00302 const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
00303 const VoidConstPtr& tracked_object = VoidConstPtr(),
00304 bool latch = false)
00305 {
00306 AdvertiseOptions ops;
00307 ops.template init<M>(topic, queue_size, connect_cb, disconnect_cb);
00308 ops.tracked_object = tracked_object;
00309 ops.latch = latch;
00310 return advertise(ops);
00311 }
00312
00334 Publisher advertise(AdvertiseOptions& ops);
00335
00336
00338
00340
00378 template<class M, class T>
00379 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), T* obj,
00380 const TransportHints& transport_hints = TransportHints())
00381 {
00382 SubscribeOptions ops;
00383 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
00384 ops.transport_hints = transport_hints;
00385 return subscribe(ops);
00386 }
00387
00389 template<class M, class T>
00390 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const, T* obj,
00391 const TransportHints& transport_hints = TransportHints())
00392 {
00393 SubscribeOptions ops;
00394 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
00395 ops.transport_hints = transport_hints;
00396 return subscribe(ops);
00397 }
00398
00437 template<class M, class T>
00438 Subscriber subscribe(const std::string& topic, uint32_t queue_size,
00439 void(T::*fp)(const boost::shared_ptr<M const>&), T* obj,
00440 const TransportHints& transport_hints = TransportHints())
00441 {
00442 SubscribeOptions ops;
00443 ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
00444 ops.transport_hints = transport_hints;
00445 return subscribe(ops);
00446 }
00447 template<class M, class T>
00448 Subscriber subscribe(const std::string& topic, uint32_t queue_size,
00449 void(T::*fp)(const boost::shared_ptr<M const>&) const, T* obj,
00450 const TransportHints& transport_hints = TransportHints())
00451 {
00452 SubscribeOptions ops;
00453 ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
00454 ops.transport_hints = transport_hints;
00455 return subscribe(ops);
00456 }
00457
00497 template<class M, class T>
00498 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M),
00499 const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
00500 {
00501 SubscribeOptions ops;
00502 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00503 ops.tracked_object = obj;
00504 ops.transport_hints = transport_hints;
00505 return subscribe(ops);
00506 }
00507
00508 template<class M, class T>
00509 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const,
00510 const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
00511 {
00512 SubscribeOptions ops;
00513 ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00514 ops.tracked_object = obj;
00515 ops.transport_hints = transport_hints;
00516 return subscribe(ops);
00517 }
00518
00558 template<class M, class T>
00559 Subscriber subscribe(const std::string& topic, uint32_t queue_size,
00560 void(T::*fp)(const boost::shared_ptr<M const>&),
00561 const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
00562 {
00563 SubscribeOptions ops;
00564 ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00565 ops.tracked_object = obj;
00566 ops.transport_hints = transport_hints;
00567 return subscribe(ops);
00568 }
00569 template<class M, class T>
00570 Subscriber subscribe(const std::string& topic, uint32_t queue_size,
00571 void(T::*fp)(const boost::shared_ptr<M const>&) const,
00572 const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
00573 {
00574 SubscribeOptions ops;
00575 ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00576 ops.tracked_object = obj;
00577 ops.transport_hints = transport_hints;
00578 return subscribe(ops);
00579 }
00580
00617 template<class M>
00618 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(M), const TransportHints& transport_hints = TransportHints())
00619 {
00620 SubscribeOptions ops;
00621 ops.template initByFullCallbackType<M>(topic, queue_size, fp);
00622 ops.transport_hints = transport_hints;
00623 return subscribe(ops);
00624 }
00625
00662 template<class M>
00663 Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr<M const>&), const TransportHints& transport_hints = TransportHints())
00664 {
00665 SubscribeOptions ops;
00666 ops.template init<M>(topic, queue_size, fp);
00667 ops.transport_hints = transport_hints;
00668 return subscribe(ops);
00669 }
00670
00705 template<class M>
00706 Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
00707 const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
00708 {
00709 SubscribeOptions ops;
00710 ops.template init<M>(topic, queue_size, callback);
00711 ops.tracked_object = tracked_object;
00712 ops.transport_hints = transport_hints;
00713 return subscribe(ops);
00714 }
00715
00751 template<class M, class C>
00752 Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (C)>& callback,
00753 const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
00754 {
00755 SubscribeOptions ops;
00756 ops.template initByFullCallbackType<C>(topic, queue_size, callback);
00757 ops.tracked_object = tracked_object;
00758 ops.transport_hints = transport_hints;
00759 return subscribe(ops);
00760 }
00761
00785 Subscriber subscribe(SubscribeOptions& ops);
00786
00788
00790
00820 template<class T, class MReq, class MRes>
00821 ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
00822 {
00823 AdvertiseServiceOptions ops;
00824 ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj, _1, _2));
00825 return advertiseService(ops);
00826 }
00827
00858 template<class T, class MReq, class MRes>
00859 ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), T *obj)
00860 {
00861 AdvertiseServiceOptions ops;
00862 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj, _1));
00863 return advertiseService(ops);
00864 }
00865
00897 template<class T, class MReq, class MRes>
00898 ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr<T>& obj)
00899 {
00900 AdvertiseServiceOptions ops;
00901 ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj.get(), _1, _2));
00902 ops.tracked_object = obj;
00903 return advertiseService(ops);
00904 }
00905
00937 template<class T, class MReq, class MRes>
00938 ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), const boost::shared_ptr<T>& obj)
00939 {
00940 AdvertiseServiceOptions ops;
00941 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj.get(), _1));
00942 ops.tracked_object = obj;
00943 return advertiseService(ops);
00944 }
00945
00974 template<class MReq, class MRes>
00975 ServiceServer advertiseService(const std::string& service, bool(*srv_func)(MReq&, MRes&))
00976 {
00977 AdvertiseServiceOptions ops;
00978 ops.template init<MReq, MRes>(service, srv_func);
00979 return advertiseService(ops);
00980 }
00981
01010 template<class MReq, class MRes>
01011 ServiceServer advertiseService(const std::string& service, bool(*srv_func)(ServiceEvent<MReq, MRes>&))
01012 {
01013 AdvertiseServiceOptions ops;
01014 ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
01015 return advertiseService(ops);
01016 }
01017
01044 template<class MReq, class MRes>
01045 ServiceServer advertiseService(const std::string& service, const boost::function<bool(MReq&, MRes&)>& callback,
01046 const VoidConstPtr& tracked_object = VoidConstPtr())
01047 {
01048 AdvertiseServiceOptions ops;
01049 ops.template init<MReq, MRes>(service, callback);
01050 ops.tracked_object = tracked_object;
01051 return advertiseService(ops);
01052 }
01053
01082 template<class S>
01083 ServiceServer advertiseService(const std::string& service, const boost::function<bool(S&)>& callback,
01084 const VoidConstPtr& tracked_object = VoidConstPtr())
01085 {
01086 AdvertiseServiceOptions ops;
01087 ops.template initBySpecType<S>(service, callback);
01088 ops.tracked_object = tracked_object;
01089 return advertiseService(ops);
01090 }
01091
01111 ServiceServer advertiseService(AdvertiseServiceOptions& ops);
01112
01114
01116
01128 template<class MReq, class MRes>
01129 ServiceClient serviceClient(const std::string& service_name, bool persistent = false,
01130 const M_string& header_values = M_string())
01131 {
01132 ServiceClientOptions ops;
01133 ops.template init<MReq, MRes>(service_name, persistent, header_values);
01134 return serviceClient(ops);
01135 }
01136
01148 template<class Service>
01149 ServiceClient serviceClient(const std::string& service_name, bool persistent = false,
01150 const M_string& header_values = M_string())
01151 {
01152 ServiceClientOptions ops;
01153 ops.template init<Service>(service_name, persistent, header_values);
01154 return serviceClient(ops);
01155 }
01156
01164 ServiceClient serviceClient(ServiceClientOptions& ops);
01165
01167
01169
01182 template<class Handler, class Obj>
01183 Timer createTimer(Rate r, Handler h, Obj o, bool oneshot = false, bool autostart = true) const
01184 {
01185 return createTimer(r.expectedCycleTime(), h, o, oneshot, autostart);
01186 }
01187
01201 template<class T>
01202 Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&) const, T* obj,
01203 bool oneshot = false, bool autostart = true) const
01204 {
01205 return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
01206 }
01207
01221 template<class T>
01222 Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), T* obj,
01223 bool oneshot = false, bool autostart = true) const
01224 {
01225 return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
01226 }
01227
01243 template<class T>
01244 Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), const boost::shared_ptr<T>& obj,
01245 bool oneshot = false, bool autostart = true) const
01246 {
01247 TimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
01248 ops.tracked_object = obj;
01249 ops.oneshot = oneshot;
01250 ops.autostart = autostart;
01251 return createTimer(ops);
01252 }
01253
01266 Timer createTimer(Duration period, const TimerCallback& callback, bool oneshot = false,
01267 bool autostart = true) const;
01268
01278 Timer createTimer(TimerOptions& ops) const;
01279
01281
01283
01298 template<class T>
01299 WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), T* obj,
01300 bool oneshot = false, bool autostart = true) const
01301 {
01302 return createWallTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
01303 }
01304
01320 template<class T>
01321 WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&),
01322 const boost::shared_ptr<T>& obj,
01323 bool oneshot = false, bool autostart = true) const
01324 {
01325 WallTimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
01326 ops.tracked_object = obj;
01327 ops.oneshot = oneshot;
01328 ops.autostart = autostart;
01329 return createWallTimer(ops);
01330 }
01331
01344 WallTimer createWallTimer(WallDuration period, const WallTimerCallback& callback,
01345 bool oneshot = false, bool autostart = true) const;
01346
01357 WallTimer createWallTimer(WallTimerOptions& ops) const;
01358
01365 void setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const;
01372 void setParam(const std::string& key, const std::string& s) const;
01379 void setParam(const std::string& key, const char* s) const;
01386 void setParam(const std::string& key, double d) const;
01393 void setParam(const std::string& key, int i) const;
01400 void setParam(const std::string& key, bool b) const;
01401
01410 bool getParam(const std::string& key, std::string& s) const;
01419 bool getParam(const std::string& key, double& d) const;
01428 bool getParam(const std::string& key, int& i) const;
01437 bool getParam(const std::string& key, bool& b) const;
01446 bool getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const;
01447
01461 bool getParamCached(const std::string& key, std::string& s) const;
01475 bool getParamCached(const std::string& key, double& d) const;
01489 bool getParamCached(const std::string& key, int& i) const;
01503 bool getParamCached(const std::string& key, bool& b) const;
01517 bool getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const;
01518
01526 bool hasParam(const std::string& key) const;
01539 bool searchParam(const std::string& key, std::string& result) const;
01547 bool deleteParam(const std::string& key) const;
01548
01561 template<typename T>
01562 void param(const std::string& param_name, T& param_val, const T& default_val) const
01563 {
01564 if (hasParam(param_name))
01565 {
01566 if (getParam(param_name, param_val))
01567 {
01568 return;
01569 }
01570 }
01571
01572 param_val = default_val;
01573 }
01574
01581 void shutdown();
01582
01590 bool ok() const;
01591
01592 private:
01593 struct no_validate { };
01594
01595 std::string resolveName(const std::string& name, bool remap, no_validate) const;
01596
01597 void construct(const std::string& ns, bool validate_name);
01598 void destruct();
01599
01600 void initRemappings(const M_string& remappings);
01601
01602 std::string remapName(const std::string& name) const;
01603
01604 std::string namespace_;
01605 std::string unresolved_namespace_;
01606 M_string remappings_;
01607 M_string unresolved_remappings_;
01608
01609 CallbackQueueInterface* callback_queue_;
01610
01611 NodeHandleBackingCollection* collection_;
01612
01613 bool ok_;
01614 };
01615
01616 }
01617
01618 #endif // ROSCPP_NODE_HANDLE_H