image_transport.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #ifndef IMAGE_TRANSPORT_IMAGE_TRANSPORT_H
00036 #define IMAGE_TRANSPORT_IMAGE_TRANSPORT_H
00037 
00038 #include "image_transport/publisher.h"
00039 #include "image_transport/subscriber.h"
00040 #include "image_transport/camera_publisher.h"
00041 #include "image_transport/camera_subscriber.h"
00042 
00043 namespace image_transport {
00044 
00051 class ImageTransport
00052 {
00053 public:
00054   explicit ImageTransport(const ros::NodeHandle& nh);
00055 
00056   ~ImageTransport();
00057 
00061   Publisher advertise(const std::string& base_topic, uint32_t queue_size, bool latch = false);
00062 
00066   Publisher advertise(const std::string& base_topic, uint32_t queue_size,
00067                       const SubscriberStatusCallback& connect_cb,
00068                       const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
00069                       const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
00070 
00074   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
00075                        const boost::function<void(const sensor_msgs::ImageConstPtr&)>& callback,
00076                        const ros::VoidPtr& tracked_object = ros::VoidPtr(),
00077                        const TransportHints& transport_hints = TransportHints());
00078 
00082   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
00083                        void(*fp)(const sensor_msgs::ImageConstPtr&),
00084                        const TransportHints& transport_hints = TransportHints())
00085   {
00086     return subscribe(base_topic, queue_size,
00087                      boost::function<void(const sensor_msgs::ImageConstPtr&)>(fp),
00088                      ros::VoidPtr(), transport_hints);
00089   }
00090 
00094   template<class T>
00095   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
00096                        void(T::*fp)(const sensor_msgs::ImageConstPtr&), T* obj,
00097                        const TransportHints& transport_hints = TransportHints())
00098   {
00099     return subscribe(base_topic, queue_size, boost::bind(fp, obj, _1), ros::VoidPtr(), transport_hints);
00100   }
00101 
00105   template<class T>
00106   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
00107                        void(T::*fp)(const sensor_msgs::ImageConstPtr&),
00108                        const boost::shared_ptr<T>& obj,
00109                        const TransportHints& transport_hints = TransportHints())
00110   {
00111     return subscribe(base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints);
00112   }
00113 
00117   CameraPublisher advertiseCamera(const std::string& base_topic, uint32_t queue_size, bool latch = false);
00118 
00123   CameraPublisher advertiseCamera(const std::string& base_topic, uint32_t queue_size,
00124                                   const SubscriberStatusCallback& image_connect_cb,
00125                                   const SubscriberStatusCallback& image_disconnect_cb = SubscriberStatusCallback(),
00126                                   const ros::SubscriberStatusCallback& info_connect_cb = ros::SubscriberStatusCallback(),
00127                                   const ros::SubscriberStatusCallback& info_disconnect_cb = ros::SubscriberStatusCallback(),
00128                                   const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
00129 
00137   CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00138                                    const CameraSubscriber::Callback& callback,
00139                                    const ros::VoidPtr& tracked_object = ros::VoidPtr(),
00140                                    const TransportHints& transport_hints = TransportHints());
00141 
00145   CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00146                                    void(*fp)(const sensor_msgs::ImageConstPtr&,
00147                                              const sensor_msgs::CameraInfoConstPtr&),
00148                                    const TransportHints& transport_hints = TransportHints())
00149   {
00150     return subscribeCamera(base_topic, queue_size, CameraSubscriber::Callback(fp), ros::VoidPtr(),
00151                            transport_hints);
00152   }
00153 
00158   template<class T>
00159   CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00160                                    void(T::*fp)(const sensor_msgs::ImageConstPtr&,
00161                                                 const sensor_msgs::CameraInfoConstPtr&), T* obj,
00162                                    const TransportHints& transport_hints = TransportHints())
00163   {
00164     return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj, _1, _2), ros::VoidPtr(),
00165                            transport_hints);
00166   }
00167 
00172   template<class T>
00173   CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00174                                    void(T::*fp)(const sensor_msgs::ImageConstPtr&,
00175                                                 const sensor_msgs::CameraInfoConstPtr&),
00176                                    const boost::shared_ptr<T>& obj,
00177                                    const TransportHints& transport_hints = TransportHints())
00178   {
00179     return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj.get(), _1, _2), obj,
00180                            transport_hints);
00181   }
00182 
00187   std::vector<std::string> getDeclaredTransports() const;
00188 
00192   std::vector<std::string> getLoadableTransports() const;
00193 
00194 private:
00195   struct Impl;
00196   typedef boost::shared_ptr<Impl> ImplPtr;
00197   typedef boost::weak_ptr<Impl> ImplWPtr;
00198 
00199   ImplPtr impl_;
00200 };
00201 
00202 } //namespace image_transport
00203 
00204 #endif


image_transport
Author(s): Patrick Mihelich
autogenerated on Thu Jun 6 2019 21:19:55