Go to the documentation of this file.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
00029
00030
00031
00032
00033
00034
00035 #ifndef MESSAGE_FILTERS_SUBSCRIBER_H
00036 #define MESSAGE_FILTERS_SUBSCRIBER_H
00037
00038 #include <ros/ros.h>
00039
00040 #include <boost/thread/mutex.hpp>
00041
00042 #include "connection.h"
00043 #include "simple_filter.h"
00044
00045 namespace message_filters
00046 {
00047
00048 class SubscriberBase
00049 {
00050 public:
00051 virtual ~SubscriberBase() {}
00063 virtual void subscribe(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints = ros::TransportHints(), ros::CallbackQueueInterface* callback_queue = 0) = 0;
00067 virtual void subscribe() = 0;
00071 virtual void unsubscribe() = 0;
00072 };
00073 typedef boost::shared_ptr<SubscriberBase> SubscriberBasePtr;
00074
00094 template<class M>
00095 class Subscriber : public SubscriberBase, public SimpleFilter<M>
00096 {
00097 public:
00098 typedef boost::shared_ptr<M const> MConstPtr;
00099 typedef ros::MessageEvent<M const> EventType;
00100
00112 Subscriber(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints = ros::TransportHints(), ros::CallbackQueueInterface* callback_queue = 0)
00113 {
00114 subscribe(nh, topic, queue_size, transport_hints, callback_queue);
00115 }
00116
00120 Subscriber()
00121 {
00122 }
00123
00124 ~Subscriber()
00125 {
00126 unsubscribe();
00127 }
00128
00140 void subscribe(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints = ros::TransportHints(), ros::CallbackQueueInterface* callback_queue = 0)
00141 {
00142 unsubscribe();
00143
00144 if (!topic.empty())
00145 {
00146 ops_.template initByFullCallbackType<const EventType&>(topic, queue_size, boost::bind(&Subscriber<M>::cb, this, _1));
00147 ops_.callback_queue = callback_queue;
00148 ops_.transport_hints = transport_hints;
00149 sub_ = nh.subscribe(ops_);
00150 nh_ = nh;
00151 }
00152 }
00153
00157 void subscribe()
00158 {
00159 unsubscribe();
00160
00161 if (!ops_.topic.empty())
00162 {
00163 sub_ = nh_.subscribe(ops_);
00164 }
00165 }
00166
00170 void unsubscribe()
00171 {
00172 sub_.shutdown();
00173 }
00174
00175 std::string getTopic() const
00176 {
00177 return ops_.topic;
00178 }
00179
00183 const ros::Subscriber& getSubscriber() const { return sub_; }
00184
00188 template<typename F>
00189 void connectInput(F& f)
00190 {
00191 (void)f;
00192 }
00193
00197 void add(const EventType& e)
00198 {
00199 (void)e;
00200 }
00201
00202 private:
00203
00204 void cb(const EventType& e)
00205 {
00206 this->signalMessage(e);
00207 }
00208
00209 ros::Subscriber sub_;
00210 ros::SubscribeOptions ops_;
00211 ros::NodeHandle nh_;
00212 };
00213
00214 }
00215
00216 #endif