subscriber_filter.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 IMAGE_TRANSPORT_SUBSCRIBER_FILTER_H
36 #define IMAGE_TRANSPORT_SUBSCRIBER_FILTER_H
37 
38 #include <ros/ros.h>
40 
42 
43 namespace image_transport {
44 
64 class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::Image>
65 {
66 public:
77  SubscriberFilter(ImageTransport& it, const std::string& base_topic, uint32_t queue_size,
78  const TransportHints& transport_hints = TransportHints())
79  {
80  subscribe(it, base_topic, queue_size, transport_hints);
81  }
82 
87  {
88  }
89 
91  {
92  unsubscribe();
93  }
94 
105  void subscribe(ImageTransport& it, const std::string& base_topic, uint32_t queue_size,
106  const TransportHints& transport_hints = TransportHints())
107  {
108  unsubscribe();
109 
110  sub_ = it.subscribe(base_topic, queue_size, boost::bind(&SubscriberFilter::cb, this, _1),
111  ros::VoidPtr(), transport_hints);
112  }
113 
117  void unsubscribe()
118  {
119  sub_.shutdown();
120  }
121 
122  std::string getTopic() const
123  {
124  return sub_.getTopic();
125  }
126 
130  uint32_t getNumPublishers() const
131  {
132  return sub_.getNumPublishers();
133  }
134 
138  std::string getTransport() const
139  {
140  return sub_.getTransport();
141  }
142 
146  const Subscriber& getSubscriber() const
147  {
148  return sub_;
149  }
150 
151 private:
152 
153  void cb(const sensor_msgs::ImageConstPtr& m)
154  {
155  signalMessage(m);
156  }
157 
159 };
160 
161 }
162 
163 #endif
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for arbitrary boost::function object.
Image subscription filter.
SubscriberFilter(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
Constructor.
std::string getTopic() const
Returns the base image topic.
Definition: subscriber.cpp:114
const Subscriber & getSubscriber() const
Returns the internal image_transport::Subscriber object.
Manages a subscription callback on a specific topic that can be interpreted as an Image topic...
Definition: subscriber.h:62
SubscriberFilter()
Empty constructor, use subscribe() to subscribe to a topic.
uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
Definition: subscriber.cpp:120
std::string getTransport() const
Returns the name of the transport being used.
uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
Subscribe to a topic.
void shutdown()
Unsubscribe the callback associated with this Subscriber.
Definition: subscriber.cpp:132
Stores transport settings for an image topic subscription.
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
std::string getTransport() const
Returns the name of the transport being used.
Definition: subscriber.cpp:126
Advertise and subscribe to image topics.
void cb(const sensor_msgs::ImageConstPtr &m)


image_transport
Author(s): Patrick Mihelich
autogenerated on Mon Feb 28 2022 22:31:45