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 
43 namespace image_transport {
44 
52 {
53 public:
54  explicit ImageTransport(const ros::NodeHandle& nh);
55 
57 
61  Publisher advertise(const std::string& base_topic, uint32_t queue_size, bool latch = false);
62 
66  Publisher advertise(const std::string& base_topic, uint32_t queue_size,
67  const SubscriberStatusCallback& connect_cb,
68  const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
69  const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
70 
74  Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
75  const boost::function<void(const sensor_msgs::ImageConstPtr&)>& callback,
76  const ros::VoidPtr& tracked_object = ros::VoidPtr(),
77  const TransportHints& transport_hints = TransportHints());
78 
82  Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
83  void(*fp)(const sensor_msgs::ImageConstPtr&),
84  const TransportHints& transport_hints = TransportHints())
85  {
86  return subscribe(base_topic, queue_size,
87  boost::function<void(const sensor_msgs::ImageConstPtr&)>(fp),
88  ros::VoidPtr(), transport_hints);
89  }
90 
94  template<class T>
95  Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
96  void(T::*fp)(const sensor_msgs::ImageConstPtr&), T* obj,
97  const TransportHints& transport_hints = TransportHints())
98  {
99  return subscribe(base_topic, queue_size, boost::bind(fp, obj, _1), ros::VoidPtr(), transport_hints);
100  }
101 
105  template<class T>
106  Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
107  void(T::*fp)(const sensor_msgs::ImageConstPtr&),
108  const boost::shared_ptr<T>& obj,
109  const TransportHints& transport_hints = TransportHints())
110  {
111  return subscribe(base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints);
112  }
113 
117  CameraPublisher advertiseCamera(const std::string& base_topic, uint32_t queue_size, bool latch = false);
118 
123  CameraPublisher advertiseCamera(const std::string& base_topic, uint32_t queue_size,
124  const SubscriberStatusCallback& image_connect_cb,
125  const SubscriberStatusCallback& image_disconnect_cb = SubscriberStatusCallback(),
127  const ros::SubscriberStatusCallback& info_disconnect_cb = ros::SubscriberStatusCallback(),
128  const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
129 
137  CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
138  const CameraSubscriber::Callback& callback,
139  const ros::VoidPtr& tracked_object = ros::VoidPtr(),
140  const TransportHints& transport_hints = TransportHints());
141 
145  CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
146  void(*fp)(const sensor_msgs::ImageConstPtr&,
147  const sensor_msgs::CameraInfoConstPtr&),
148  const TransportHints& transport_hints = TransportHints())
149  {
150  return subscribeCamera(base_topic, queue_size, CameraSubscriber::Callback(fp), ros::VoidPtr(),
151  transport_hints);
152  }
153 
158  template<class T>
159  CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
160  void(T::*fp)(const sensor_msgs::ImageConstPtr&,
161  const sensor_msgs::CameraInfoConstPtr&), T* obj,
162  const TransportHints& transport_hints = TransportHints())
163  {
164  return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj, _1, _2), ros::VoidPtr(),
165  transport_hints);
166  }
167 
172  template<class T>
173  CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
174  void(T::*fp)(const sensor_msgs::ImageConstPtr&,
175  const sensor_msgs::CameraInfoConstPtr&),
176  const boost::shared_ptr<T>& obj,
177  const TransportHints& transport_hints = TransportHints())
178  {
179  return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj.get(), _1, _2), obj,
180  transport_hints);
181  }
182 
187  std::vector<std::string> getDeclaredTransports() const;
188 
192  std::vector<std::string> getLoadableTransports() const;
193 
194 private:
195  struct Impl;
197  typedef boost::weak_ptr<Impl> ImplWPtr;
198 
199  ImplPtr impl_;
200 };
201 
202 } //namespace image_transport
203 
204 #endif
Manages advertisements of multiple transport options on an Image topic.
Definition: publisher.h:63
std::vector< std::string > getLoadableTransports() const
Returns the names of all transports that are loadable in the system.
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.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ImageTransport(const ros::NodeHandle &nh)
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for class member function with ba...
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for arbitrary boost::function obj...
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
Manages advertisements for publishing camera images.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for class member function with bare pointer. ...
Manages a subscription callback on a specific topic that can be interpreted as an Image topic...
Definition: subscriber.h:61
Manages a subscription callback on synchronized Image and CameraInfo topics.
boost::shared_ptr< Impl > ImplPtr
boost::weak_ptr< Impl > ImplWPtr
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise a synchronized camera raw image + info topic pair, simple version.
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for bare function.
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for class member function with sh...
std::vector< std::string > getDeclaredTransports() const
Returns the names of all transports declared in the system. Declared transports are not necessarily b...
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &), const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for bare function.
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Stores transport settings for an image topic subscription.
Advertise and subscribe to image topics.
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for class member function with shared_ptr.


image_transport
Author(s): Patrick Mihelich
autogenerated on Thu Jun 6 2019 19:22:47