image_transport.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_IMAGE_TRANSPORT_H
36 #define IMAGE_TRANSPORT_IMAGE_TRANSPORT_H
37 
42 #include "exports.h"
43 
44 namespace image_transport {
45 
52 class IMAGE_TRANSPORT_DECL ImageTransport
53 {
54 public:
55  explicit ImageTransport(const ros::NodeHandle& nh);
56 
57  ~ImageTransport();
58 
62  Publisher advertise(const std::string& base_topic, uint32_t queue_size, bool latch = false);
63 
67  Publisher advertise(const std::string& base_topic, uint32_t queue_size,
68  const SubscriberStatusCallback& connect_cb,
69  const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
70  const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
71 
75  Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
76  const boost::function<void(const sensor_msgs::ImageConstPtr&)>& callback,
77  const ros::VoidPtr& tracked_object = ros::VoidPtr(),
78  const TransportHints& transport_hints = TransportHints());
79 
83  Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
84  void(*fp)(const sensor_msgs::ImageConstPtr&),
85  const TransportHints& transport_hints = TransportHints())
86  {
87  return subscribe(base_topic, queue_size,
88  boost::function<void(const sensor_msgs::ImageConstPtr&)>(fp),
89  ros::VoidPtr(), transport_hints);
90  }
91 
95  template<class T>
96  Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
97  void(T::*fp)(const sensor_msgs::ImageConstPtr&), T* obj,
98  const TransportHints& transport_hints = TransportHints())
99  {
100  return subscribe(base_topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1), ros::VoidPtr(), transport_hints);
101  }
102 
106  template<class T>
107  Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
108  void(T::*fp)(const sensor_msgs::ImageConstPtr&),
109  const boost::shared_ptr<T>& obj,
110  const TransportHints& transport_hints = TransportHints())
111  {
112  return subscribe(base_topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1), obj, transport_hints);
113  }
114 
118  CameraPublisher advertiseCamera(const std::string& base_topic, uint32_t queue_size, bool latch = false);
119 
124  CameraPublisher advertiseCamera(const std::string& base_topic, uint32_t queue_size,
125  const SubscriberStatusCallback& image_connect_cb,
126  const SubscriberStatusCallback& image_disconnect_cb = SubscriberStatusCallback(),
128  const ros::SubscriberStatusCallback& info_disconnect_cb = ros::SubscriberStatusCallback(),
129  const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
130 
138  CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
139  const CameraSubscriber::Callback& callback,
140  const ros::VoidPtr& tracked_object = ros::VoidPtr(),
141  const TransportHints& transport_hints = TransportHints());
142 
146  CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
147  void(*fp)(const sensor_msgs::ImageConstPtr&,
148  const sensor_msgs::CameraInfoConstPtr&),
149  const TransportHints& transport_hints = TransportHints())
150  {
151  return subscribeCamera(base_topic, queue_size, CameraSubscriber::Callback(fp), ros::VoidPtr(),
152  transport_hints);
153  }
154 
159  template<class T>
160  CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
161  void(T::*fp)(const sensor_msgs::ImageConstPtr&,
162  const sensor_msgs::CameraInfoConstPtr&), T* obj,
163  const TransportHints& transport_hints = TransportHints())
164  {
165  return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj, boost::placeholders::_1, boost::placeholders::_2), ros::VoidPtr(),
166  transport_hints);
167  }
168 
173  template<class T>
174  CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
175  void(T::*fp)(const sensor_msgs::ImageConstPtr&,
176  const sensor_msgs::CameraInfoConstPtr&),
177  const boost::shared_ptr<T>& obj,
178  const TransportHints& transport_hints = TransportHints())
179  {
180  return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj.get(), boost::placeholders::_1, boost::placeholders::_2), obj,
181  transport_hints);
182  }
183 
188  std::vector<std::string> getDeclaredTransports() const;
189 
193  std::vector<std::string> getLoadableTransports() const;
194 
195 private:
196  struct Impl;
197  typedef boost::shared_ptr<Impl> ImplPtr;
198  typedef boost::weak_ptr<Impl> ImplWPtr;
199 
200  ImplPtr impl_;
201 };
202 
203 } //namespace image_transport
204 
205 #endif
boost::shared_ptr< void >
camera_subscriber.h
subscriber.h
SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
image_transport::Subscriber
Manages a subscription callback on a specific topic that can be interpreted as an Image topic.
Definition: subscriber.h:94
image_transport::CameraSubscriber
Manages a subscription callback on synchronized Image and CameraInfo topics.
Definition: camera_subscriber.h:95
exports.h
image_transport::CameraSubscriber::Callback
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Definition: camera_subscriber.h:99
publisher.h
image_transport
Definition: camera_common.h:41
camera_publisher.h
image_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Definition: single_subscriber_publisher.h:109
image_transport::TransportHints
Stores transport settings for an image topic subscription.
Definition: transport_hints.h:77
IMAGE_TRANSPORT_DECL
#define IMAGE_TRANSPORT_DECL
Definition: exports.h:15
ros::NodeHandle


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50