subscriber.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef MESSAGE_FILTERS_SUBSCRIBER_H
36 #define MESSAGE_FILTERS_SUBSCRIBER_H
37 
38 #include <ros/ros.h>
39 
40 #include <boost/thread/mutex.hpp>
41 
42 #include "connection.h"
43 #include "simple_filter.h"
44 
45 namespace message_filters
46 {
47 
48 class SubscriberBase
49 {
50 public:
51  virtual ~SubscriberBase() {}
63  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;
67  virtual void subscribe() = 0;
71  virtual void unsubscribe() = 0;
72 };
74 
94 template<class M>
95 class Subscriber : public SubscriberBase, public SimpleFilter<M>
96 {
97 public:
100 
112  Subscriber(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints = ros::TransportHints(), ros::CallbackQueueInterface* callback_queue = 0)
113  {
114  subscribe(nh, topic, queue_size, transport_hints, callback_queue);
115  }
116 
120  Subscriber()
121  {
122  }
123 
124  ~Subscriber()
125  {
127  }
128 
140  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)
141  {
142  unsubscribe();
143 
144  if (!topic.empty())
145  {
146  ops_.template initByFullCallbackType<const EventType&>(topic, queue_size, boost::bind(&Subscriber<M>::cb, this, boost::placeholders::_1));
147  ops_.callback_queue = callback_queue;
148  ops_.transport_hints = transport_hints;
149  sub_ = nh.subscribe(ops_);
150  nh_ = nh;
151  }
152  }
153 
157  void subscribe()
158  {
159  unsubscribe();
160 
161  if (!ops_.topic.empty())
162  {
163  sub_ = nh_.subscribe(ops_);
164  }
165  }
166 
170  void unsubscribe()
171  {
173  }
174 
175  std::string getTopic() const
176  {
177  return ops_.topic;
178  }
179 
183  const ros::Subscriber& getSubscriber() const { return sub_; }
184 
188  template<typename F>
189  void connectInput(F& f)
190  {
191  (void)f;
192  }
193 
197  void add(const EventType& e)
198  {
199  (void)e;
200  }
201 
202 private:
203 
204  void cb(const EventType& e)
205  {
206  this->signalMessage(e);
207  }
208 
212 };
213 
214 }
215 
216 #endif
boost::shared_ptr
message_filters::Subscriber::cb
void cb(const EventType &e)
Definition: subscriber.h:236
ros.h
message_filters::SubscriberBase::~SubscriberBase
virtual ~SubscriberBase()
Definition: subscriber.h:115
ros::SubscribeOptions::topic
std::string topic
ros::SubscribeOptions::transport_hints
TransportHints transport_hints
ros::TransportHints
ros::SubscribeOptions::callback_queue
CallbackQueueInterface * callback_queue
simple_filter.h
ros::Subscriber::shutdown
void shutdown()
message_filters::Subscriber::unsubscribe
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
Definition: subscriber.h:202
f
f
message_filters::Subscriber::getTopic
std::string getTopic() const
Definition: subscriber.h:207
message_filters::Subscriber
ROS subscription filter.
Definition: subscriber.h:127
message_filters::Subscriber::MConstPtr
boost::shared_ptr< M const > MConstPtr
Definition: subscriber.h:130
message_filters::Subscriber::sub_
ros::Subscriber sub_
Definition: subscriber.h:241
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
message_filters::Subscriber::subscribe
void subscribe()
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
Definition: subscriber.h:189
connection.h
message_filters::Subscriber::ops_
ros::SubscribeOptions ops_
Definition: subscriber.h:242
ros::SubscribeOptions
message_filters::Subscriber::connectInput
void connectInput(F &f)
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
Definition: subscriber.h:221
message_filters::SubscriberBase::subscribe
virtual void subscribe()=0
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
message_filters::SubscriberBase::unsubscribe
virtual void unsubscribe()=0
Force immediate unsubscription of this subscriber from its topic.
message_filters::Subscriber::nh_
ros::NodeHandle nh_
Definition: subscriber.h:243
message_filters
Definition: cache.h:47
message_filters::Subscriber::getSubscriber
const ros::Subscriber & getSubscriber() const
Returns the internal ros::Subscriber object.
Definition: subscriber.h:215
message_filters::Subscriber::~Subscriber
~Subscriber()
Definition: subscriber.h:156
message_filters::SimpleFilter::signalMessage
void signalMessage(const MConstPtr &msg)
Call all registered callbacks, passing them the specified message.
Definition: simple_filter.h:188
message_filters::Subscriber::add
void add(const EventType &e)
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
Definition: subscriber.h:229
message_filters::Subscriber::EventType
ros::MessageEvent< M const > EventType
Definition: subscriber.h:131
message_filters::Subscriber::Subscriber
Subscriber()
Empty constructor, use subscribe() to subscribe to a topic.
Definition: subscriber.h:152
ros::CallbackQueueInterface
ros::NodeHandle
ros::MessageEvent
ros::Subscriber
message_filters::SubscriberBasePtr
boost::shared_ptr< SubscriberBase > SubscriberBasePtr
Definition: subscriber.h:105


message_filters
Author(s): Josh Faust, Vijay Pradeep, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:54