node_handle.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2009, Willow Garage, Inc.
00003  *
00004  * Redistribution and use in source and binary forms, with or without
00005  * modification, are permitted provided that the following conditions are met:
00006  *   * Redistributions of source code must retain the above copyright notice,
00007  *     this list of conditions and the following disclaimer.
00008  *   * Redistributions in binary form must reproduce the above copyright
00009  *     notice, this list of conditions and the following disclaimer in the
00010  *     documentation and/or other materials provided with the distribution.
00011  *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
00012  *     contributors may be used to endorse or promote products derived from
00013  *     this software without specific prior written permission.
00014  *
00015  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025  * POSSIBILITY OF SUCH DAMAGE.
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);
00133     NodeHandle(const NodeHandle& parent, const std::string& ns);
00155     NodeHandle(const NodeHandle& parent, const std::string& ns, const M_string& remappings);
00163     ~NodeHandle();
00164 
00165     NodeHandle& operator=(const NodeHandle& rhs);
00166 
00175     void setCallbackQueue(CallbackQueueInterface* queue);
00176 
00182     CallbackQueueInterface* getCallbackQueue() const 
00183     { 
00184       return callback_queue_ ? callback_queue_ : (CallbackQueueInterface*)getGlobalCallbackQueue(); 
00185     }
00186 
00190     const std::string& getNamespace() const { return namespace_; }
00191 
00196     const std::string& getUnresolvedNamespace() const { return unresolved_namespace_; }
00197 
00214     std::string resolveName(const std::string& name, bool remap = true) const;
00215 
00217     // Versions of advertise()
00219 
00247     template <class M>
00248     Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false)
00249     {
00250       AdvertiseOptions ops;
00251       ops.template init<M>(topic, queue_size);
00252       ops.latch = latch;
00253       return advertise(ops);
00254     }
00255 
00313   template <class M>
00314   Publisher advertise(const std::string& topic, uint32_t queue_size,
00315                             const SubscriberStatusCallback& connect_cb,
00316                             const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
00317                             const VoidConstPtr& tracked_object = VoidConstPtr(),
00318                             bool latch = false)
00319   {
00320     AdvertiseOptions ops;
00321     ops.template init<M>(topic, queue_size, connect_cb, disconnect_cb);
00322     ops.tracked_object = tracked_object;
00323     ops.latch = latch;
00324     return advertise(ops);
00325   }
00326 
00352   Publisher advertise(AdvertiseOptions& ops);
00353 
00354 
00356   // Versions of subscribe()
00358 
00400   template<class M, class T>
00401   Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), T* obj, 
00402                        const TransportHints& transport_hints = TransportHints())
00403   {
00404     SubscribeOptions ops;
00405     ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
00406     ops.transport_hints = transport_hints;
00407     return subscribe(ops);
00408   }
00409 
00411   template<class M, class T>
00412   Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const, T* obj, 
00413                        const TransportHints& transport_hints = TransportHints())
00414   {
00415     SubscribeOptions ops;
00416     ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
00417     ops.transport_hints = transport_hints;
00418     return subscribe(ops);
00419   }
00420 
00463   template<class M, class T>
00464   Subscriber subscribe(const std::string& topic, uint32_t queue_size, 
00465                        void(T::*fp)(const boost::shared_ptr<M const>&), T* obj, 
00466                        const TransportHints& transport_hints = TransportHints())
00467   {
00468     SubscribeOptions ops;
00469     ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
00470     ops.transport_hints = transport_hints;
00471     return subscribe(ops);
00472   }
00473   template<class M, class T>
00474   Subscriber subscribe(const std::string& topic, uint32_t queue_size, 
00475                        void(T::*fp)(const boost::shared_ptr<M const>&) const, T* obj, 
00476                        const TransportHints& transport_hints = TransportHints())
00477   {
00478     SubscribeOptions ops;
00479     ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
00480     ops.transport_hints = transport_hints;
00481     return subscribe(ops);
00482   }
00483 
00527   template<class M, class T>
00528   Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), 
00529                        const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
00530   {
00531     SubscribeOptions ops;
00532     ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00533     ops.tracked_object = obj;
00534     ops.transport_hints = transport_hints;
00535     return subscribe(ops);
00536   }
00537 
00538   template<class M, class T>
00539   Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const, 
00540                        const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
00541   {
00542     SubscribeOptions ops;
00543     ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00544     ops.tracked_object = obj;
00545     ops.transport_hints = transport_hints;
00546     return subscribe(ops);
00547   }
00548 
00592   template<class M, class T>
00593   Subscriber subscribe(const std::string& topic, uint32_t queue_size, 
00594                        void(T::*fp)(const boost::shared_ptr<M const>&), 
00595                        const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
00596   {
00597     SubscribeOptions ops;
00598     ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00599     ops.tracked_object = obj;
00600     ops.transport_hints = transport_hints;
00601     return subscribe(ops);
00602   }
00603   template<class M, class T>
00604   Subscriber subscribe(const std::string& topic, uint32_t queue_size, 
00605                        void(T::*fp)(const boost::shared_ptr<M const>&) const, 
00606                        const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
00607   {
00608     SubscribeOptions ops;
00609     ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
00610     ops.tracked_object = obj;
00611     ops.transport_hints = transport_hints;
00612     return subscribe(ops);
00613   }
00614 
00654   template<class M>
00655   Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(M), const TransportHints& transport_hints = TransportHints())
00656   {
00657     SubscribeOptions ops;
00658     ops.template initByFullCallbackType<M>(topic, queue_size, fp);
00659     ops.transport_hints = transport_hints;
00660     return subscribe(ops);
00661   }
00662 
00702   template<class M>
00703   Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr<M const>&), const TransportHints& transport_hints = TransportHints())
00704   {
00705     SubscribeOptions ops;
00706     ops.template init<M>(topic, queue_size, fp);
00707     ops.transport_hints = transport_hints;
00708     return subscribe(ops);
00709   }
00710 
00748   template<class M>
00749   Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
00750                              const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
00751   {
00752     SubscribeOptions ops;
00753     ops.template init<M>(topic, queue_size, callback);
00754     ops.tracked_object = tracked_object;
00755     ops.transport_hints = transport_hints;
00756     return subscribe(ops);
00757   }
00758 
00797   template<class M, class C>
00798   Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (C)>& callback,
00799                              const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
00800   {
00801     SubscribeOptions ops;
00802     ops.template initByFullCallbackType<C>(topic, queue_size, callback);
00803     ops.tracked_object = tracked_object;
00804     ops.transport_hints = transport_hints;
00805     return subscribe(ops);
00806   }
00807 
00835   Subscriber subscribe(SubscribeOptions& ops);
00836 
00838   // Versions of advertiseService()
00840 
00877   template<class T, class MReq, class MRes>
00878   ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
00879   {
00880     AdvertiseServiceOptions ops;
00881     ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj, _1, _2));
00882     return advertiseService(ops);
00883   }
00884 
00922   template<class T, class MReq, class MRes>
00923   ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), T *obj)
00924   {
00925     AdvertiseServiceOptions ops;
00926     ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj, _1));
00927     return advertiseService(ops);
00928   }
00929 
00968   template<class T, class MReq, class MRes>
00969   ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr<T>& obj)
00970   {
00971     AdvertiseServiceOptions ops;
00972     ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj.get(), _1, _2));
00973     ops.tracked_object = obj;
00974     return advertiseService(ops);
00975   }
00976 
01015   template<class T, class MReq, class MRes>
01016   ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), const boost::shared_ptr<T>& obj)
01017   {
01018     AdvertiseServiceOptions ops;
01019     ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj.get(), _1));
01020     ops.tracked_object = obj;
01021     return advertiseService(ops);
01022   }
01023 
01059   template<class MReq, class MRes>
01060   ServiceServer advertiseService(const std::string& service, bool(*srv_func)(MReq&, MRes&))
01061   {
01062     AdvertiseServiceOptions ops;
01063     ops.template init<MReq, MRes>(service, srv_func);
01064     return advertiseService(ops);
01065   }
01066 
01102   template<class MReq, class MRes>
01103   ServiceServer advertiseService(const std::string& service, bool(*srv_func)(ServiceEvent<MReq, MRes>&))
01104   {
01105     AdvertiseServiceOptions ops;
01106     ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
01107     return advertiseService(ops);
01108   }
01109 
01143   template<class MReq, class MRes>
01144   ServiceServer advertiseService(const std::string& service, const boost::function<bool(MReq&, MRes&)>& callback, 
01145                                  const VoidConstPtr& tracked_object = VoidConstPtr())
01146   {
01147     AdvertiseServiceOptions ops;
01148     ops.template init<MReq, MRes>(service, callback);
01149     ops.tracked_object = tracked_object;
01150     return advertiseService(ops);
01151   }
01152 
01188   template<class S>
01189   ServiceServer advertiseService(const std::string& service, const boost::function<bool(S&)>& callback, 
01190                                  const VoidConstPtr& tracked_object = VoidConstPtr())
01191   {
01192     AdvertiseServiceOptions ops;
01193     ops.template initBySpecType<S>(service, callback);
01194     ops.tracked_object = tracked_object;
01195     return advertiseService(ops);
01196   }
01197 
01221   ServiceServer advertiseService(AdvertiseServiceOptions& ops);
01222 
01224   // Versions of serviceClient()
01226 
01238   template<class MReq, class MRes>
01239   ServiceClient serviceClient(const std::string& service_name, bool persistent = false, 
01240                               const M_string& header_values = M_string())
01241   {
01242     ServiceClientOptions ops;
01243     ops.template init<MReq, MRes>(service_name, persistent, header_values);
01244     return serviceClient(ops);
01245   }
01246 
01258   template<class Service>
01259   ServiceClient serviceClient(const std::string& service_name, bool persistent = false, 
01260                               const M_string& header_values = M_string())
01261   {
01262     ServiceClientOptions ops;
01263     ops.template init<Service>(service_name, persistent, header_values);
01264     return serviceClient(ops);
01265   }
01266 
01274   ServiceClient serviceClient(ServiceClientOptions& ops);
01275 
01277   // Versions of createTimer()
01279 
01292   template<class Handler, class Obj>
01293   Timer createTimer(Rate r, Handler h, Obj o, bool oneshot = false, bool autostart = true) const
01294   {
01295     return createTimer(r.expectedCycleTime(), h, o, oneshot, autostart);
01296   }
01297 
01311   template<class T>
01312   Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&) const, T* obj, 
01313                     bool oneshot = false, bool autostart = true) const
01314   {
01315     return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
01316   }
01317 
01331   template<class T>
01332   Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), T* obj, 
01333                     bool oneshot = false, bool autostart = true) const
01334   {
01335     return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
01336   }
01337 
01353   template<class T>
01354   Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), const boost::shared_ptr<T>& obj, 
01355                     bool oneshot = false, bool autostart = true) const
01356   {
01357     TimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
01358     ops.tracked_object = obj;
01359     ops.oneshot = oneshot;
01360     ops.autostart = autostart;
01361     return createTimer(ops);
01362   }
01363 
01376   Timer createTimer(Duration period, const TimerCallback& callback, bool oneshot = false,
01377                     bool autostart = true) const;
01378 
01388   Timer createTimer(TimerOptions& ops) const;
01389 
01391   // Versions of createWallTimer()
01393 
01408   template<class T>
01409   WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), T* obj, 
01410                             bool oneshot = false, bool autostart = true) const
01411   {
01412     return createWallTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
01413   }
01414 
01430   template<class T>
01431   WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), 
01432                             const boost::shared_ptr<T>& obj, 
01433                             bool oneshot = false, bool autostart = true) const
01434   {
01435     WallTimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
01436     ops.tracked_object = obj;
01437     ops.oneshot = oneshot;
01438     ops.autostart = autostart;
01439     return createWallTimer(ops);
01440   }
01441 
01454   WallTimer createWallTimer(WallDuration period, const WallTimerCallback& callback, 
01455                             bool oneshot = false, bool autostart = true) const;
01456 
01467   WallTimer createWallTimer(WallTimerOptions& ops) const;
01468 
01475   void setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const;
01482   void setParam(const std::string& key, const std::string& s) const;
01489   void setParam(const std::string& key, const char* s) const;
01496   void setParam(const std::string& key, double d) const;
01503   void setParam(const std::string& key, int i) const;
01510   void setParam(const std::string& key, bool b) const;
01511 
01518   void setParam(const std::string& key, const std::vector<std::string>& vec) const;
01525   void setParam(const std::string& key, const std::vector<double>& vec) const;
01532   void setParam(const std::string& key, const std::vector<float>& vec) const;
01539   void setParam(const std::string& key, const std::vector<int>& vec) const;
01546   void setParam(const std::string& key, const std::vector<bool>& vec) const;
01547 
01554   void setParam(const std::string& key, const std::map<std::string, std::string>& map) const;
01561   void setParam(const std::string& key, const std::map<std::string, double>& map) const;
01568   void setParam(const std::string& key, const std::map<std::string, float>& map) const;
01575   void setParam(const std::string& key, const std::map<std::string, int>& map) const;
01582   void setParam(const std::string& key, const std::map<std::string, bool>& map) const;
01583 
01592   bool getParam(const std::string& key, std::string& s) const;
01603   bool getParam(const std::string& key, double& d) const;
01614   bool getParam(const std::string& key, float& f) const;
01625   bool getParam(const std::string& key, int& i) const;
01636   bool getParam(const std::string& key, bool& b) const;
01647   bool getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const;
01648 
01659   bool getParam(const std::string& key, std::vector<std::string>& vec) const;
01670   bool getParam(const std::string& key, std::vector<double>& vec) const;
01681   bool getParam(const std::string& key, std::vector<float>& vec) const;
01692   bool getParam(const std::string& key, std::vector<int>& vec) const;
01703   bool getParam(const std::string& key, std::vector<bool>& vec) const;
01704 
01715   bool getParam(const std::string& key, std::map<std::string, std::string>& map) const;
01726   bool getParam(const std::string& key, std::map<std::string, double>& map) const;
01737   bool getParam(const std::string& key, std::map<std::string, float>& map) const;
01748   bool getParam(const std::string& key, std::map<std::string, int>& map) const;
01759   bool getParam(const std::string& key, std::map<std::string, bool>& map) const;
01760 
01776   bool getParamCached(const std::string& key, std::string& s) const;
01790   bool getParamCached(const std::string& key, double& d) const;
01804   bool getParamCached(const std::string& key, float& f) const;
01818   bool getParamCached(const std::string& key, int& i) const;
01832   bool getParamCached(const std::string& key, bool& b) const;
01846   bool getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const;
01847 
01861   bool getParamCached(const std::string& key, std::vector<std::string>& vec) const;
01875   bool getParamCached(const std::string& key, std::vector<double>& vec) const;
01889   bool getParamCached(const std::string& key, std::vector<float>& vec) const;
01903   bool getParamCached(const std::string& key, std::vector<int>& vec) const;
01917   bool getParamCached(const std::string& key, std::vector<bool>& vec) const;
01918 
01932   bool getParamCached(const std::string& key, std::map<std::string, std::string>& map) const;
01946   bool getParamCached(const std::string& key, std::map<std::string, double>& map) const;
01960   bool getParamCached(const std::string& key, std::map<std::string, float>& map) const;
01974   bool getParamCached(const std::string& key, std::map<std::string, int>& map) const;
01988   bool getParamCached(const std::string& key, std::map<std::string, bool>& map) const;
01989 
01997   bool hasParam(const std::string& key) const;
02010   bool searchParam(const std::string& key, std::string& result) const;
02018   bool deleteParam(const std::string& key) const;
02019 
02024   bool getParamNames(std::vector<std::string>& keys) const;
02025 
02038   template<typename T>
02039   void param(const std::string& param_name, T& param_val, const T& default_val) const
02040   {
02041     if (hasParam(param_name))
02042     {
02043       if (getParam(param_name, param_val))
02044       {
02045         return;
02046       }
02047     }
02048 
02049     param_val = default_val;
02050   }
02051 
02070   template<typename T>
02071   T param(const std::string& param_name, const T& default_val)
02072   {
02073       T param_val;
02074       param(param_name, param_val, default_val);
02075       return param_val;
02076   }
02077 
02084   void shutdown();
02085 
02093   bool ok() const;
02094 
02095 private:
02096   struct no_validate { };
02097   // this is pretty awful, but required to preserve public interface (and make minimum possible changes)
02098   std::string resolveName(const std::string& name, bool remap, no_validate) const;
02099 
02100   void construct(const std::string& ns, bool validate_name);
02101   void destruct();
02102 
02103   void initRemappings(const M_string& remappings);
02104 
02105   std::string remapName(const std::string& name) const;
02106 
02107   std::string namespace_;
02108   std::string unresolved_namespace_;
02109   M_string remappings_;
02110   M_string unresolved_remappings_;
02111 
02112   CallbackQueueInterface* callback_queue_;
02113 
02114   NodeHandleBackingCollection* collection_;
02115 
02116   bool ok_;
02117 };
02118 
02119 }
02120 
02121 #endif // ROSCPP_NODE_HANDLE_H


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:44:47