$search
00001 #ifndef MESSAGE_TRANSPORT_MESSAGE_TRANSPORT_H 00002 #define MESSAGE_TRANSPORT_MESSAGE_TRANSPORT_H 00003 00004 #include "message_transport/publisher.h" 00005 #include "message_transport/subscriber.h" 00006 00007 namespace message_transport { 00008 00015 template <class M> 00016 class MessageTransport 00017 { 00018 public: 00019 explicit MessageTransport(const ros::NodeHandle& nh, 00020 const std::string & package_name, 00021 const std::string & class_name) 00022 : nh_(nh), package_name_(package_name), class_name_(class_name) { 00023 } 00024 00025 ~MessageTransport() { 00026 } 00027 00031 Publisher advertise(const std::string& base_topic, uint32_t queue_size, bool latch = false) 00032 { 00033 return advertise(base_topic, queue_size, 00034 typename SingleSubscriberPublisher<M>::StatusCB(), 00035 typename SingleSubscriberPublisher<M>::StatusCB(), 00036 ros::VoidPtr(), latch); 00037 } 00038 00042 Publisher advertise(const std::string& base_topic, uint32_t queue_size, 00043 const typename SingleSubscriberPublisher<M>::StatusCB& connect_cb, 00044 const typename SingleSubscriberPublisher<M>::StatusCB& disconnect_cb = SingleSubscriberPublisher<M>::StatusCB(), 00045 const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false) 00046 { 00047 Publisher p(nh_); 00048 p.do_initialise<M>(nh_, package_name_, class_name_, 00049 base_topic, queue_size, 00050 connect_cb, disconnect_cb, tracked_object, latch); 00051 return p; 00052 } 00053 00057 Subscriber subscribe(const std::string& base_topic, uint32_t queue_size, 00058 const boost::function<void(const typename M::ConstPtr&)>& callback, 00059 const ros::VoidPtr& tracked_object = ros::VoidPtr(), 00060 const TransportHints& transport_hints = TransportHints()) 00061 { 00062 Subscriber s(nh_); 00063 s.do_subscribe<M>(nh_, package_name_, class_name_, 00064 base_topic, queue_size, 00065 callback, tracked_object, transport_hints); 00066 return s; 00067 } 00068 00069 00073 Subscriber subscribe(const std::string& base_topic, uint32_t queue_size, 00074 void(*fp)(const typename M::ConstPtr&), 00075 const TransportHints& transport_hints = TransportHints()) 00076 { 00077 return subscribe(base_topic, queue_size, 00078 boost::function<void(const typename M::ConstPtr&)>(fp), 00079 ros::VoidPtr(), transport_hints); 00080 } 00081 00085 template<class T> 00086 Subscriber subscribe(const std::string& base_topic, uint32_t queue_size, 00087 void(T::*fp)(const typename M::ConstPtr&), T* obj, 00088 const TransportHints& transport_hints = TransportHints()) 00089 { 00090 return subscribe(base_topic, queue_size, boost::bind(fp, obj, _1), ros::VoidPtr(), transport_hints); 00091 } 00092 00096 template<class T> 00097 Subscriber subscribe(const std::string& base_topic, uint32_t queue_size, 00098 void(T::*fp)(const typename M::ConstPtr&), 00099 const boost::shared_ptr<T>& obj, 00100 const TransportHints& transport_hints = TransportHints()) 00101 { 00102 return subscribe(base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints); 00103 } 00104 00106 //void shutdown(); 00107 00108 protected: 00109 ros::NodeHandle nh_; 00110 std::string package_name_; 00111 std::string class_name_; 00112 }; 00113 00114 } //namespace message_transport 00115 00116 #endif