image_transport.h
Go to the documentation of this file.
00001 #ifndef IMAGE_TRANSPORT_IMAGE_TRANSPORT_H
00002 #define IMAGE_TRANSPORT_IMAGE_TRANSPORT_H
00003 
00004 #include "image_transport/publisher.h"
00005 #include "image_transport/subscriber.h"
00006 #include "image_transport/camera_publisher.h"
00007 #include "image_transport/camera_subscriber.h"
00008 
00009 namespace image_transport {
00010 
00017 class ImageTransport
00018 {
00019 public:
00020   explicit ImageTransport(const ros::NodeHandle& nh);
00021 
00022   ~ImageTransport();
00023 
00027   Publisher advertise(const std::string& base_topic, uint32_t queue_size, bool latch = false);
00028 
00032   Publisher advertise(const std::string& base_topic, uint32_t queue_size,
00033                       const SubscriberStatusCallback& connect_cb,
00034                       const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
00035                       const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
00036 
00040   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
00041                        const boost::function<void(const sensor_msgs::ImageConstPtr&)>& callback,
00042                        const ros::VoidPtr& tracked_object = ros::VoidPtr(),
00043                        const TransportHints& transport_hints = TransportHints());
00044 
00048   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
00049                        void(*fp)(const sensor_msgs::ImageConstPtr&),
00050                        const TransportHints& transport_hints = TransportHints())
00051   {
00052     return subscribe(base_topic, queue_size,
00053                      boost::function<void(const sensor_msgs::ImageConstPtr&)>(fp),
00054                      ros::VoidPtr(), transport_hints);
00055   }
00056 
00060   template<class T>
00061   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
00062                        void(T::*fp)(const sensor_msgs::ImageConstPtr&), T* obj,
00063                        const TransportHints& transport_hints = TransportHints())
00064   {
00065     return subscribe(base_topic, queue_size, boost::bind(fp, obj, _1), ros::VoidPtr(), transport_hints);
00066   }
00067 
00071   template<class T>
00072   Subscriber subscribe(const std::string& base_topic, uint32_t queue_size,
00073                        void(T::*fp)(const sensor_msgs::ImageConstPtr&),
00074                        const boost::shared_ptr<T>& obj,
00075                        const TransportHints& transport_hints = TransportHints())
00076   {
00077     return subscribe(base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints);
00078   }
00079 
00083   CameraPublisher advertiseCamera(const std::string& base_topic, uint32_t queue_size, bool latch = false);
00084 
00089   CameraPublisher advertiseCamera(const std::string& base_topic, uint32_t queue_size,
00090                                   const SubscriberStatusCallback& image_connect_cb,
00091                                   const SubscriberStatusCallback& image_disconnect_cb = SubscriberStatusCallback(),
00092                                   const ros::SubscriberStatusCallback& info_connect_cb = ros::SubscriberStatusCallback(),
00093                                   const ros::SubscriberStatusCallback& info_disconnect_cb = ros::SubscriberStatusCallback(),
00094                                   const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = false);
00095 
00103   CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00104                                    const CameraSubscriber::Callback& callback,
00105                                    const ros::VoidPtr& tracked_object = ros::VoidPtr(),
00106                                    const TransportHints& transport_hints = TransportHints());
00107 
00111   CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00112                                    void(*fp)(const sensor_msgs::ImageConstPtr&,
00113                                              const sensor_msgs::CameraInfoConstPtr&),
00114                                    const TransportHints& transport_hints = TransportHints())
00115   {
00116     return subscribeCamera(base_topic, queue_size, CameraSubscriber::Callback(fp), ros::VoidPtr(),
00117                            transport_hints);
00118   }
00119 
00124   template<class T>
00125   CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00126                                    void(T::*fp)(const sensor_msgs::ImageConstPtr&,
00127                                                 const sensor_msgs::CameraInfoConstPtr&), T* obj,
00128                                    const TransportHints& transport_hints = TransportHints())
00129   {
00130     return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj, _1, _2), ros::VoidPtr(),
00131                            transport_hints);
00132   }
00133 
00138   template<class T>
00139   CameraSubscriber subscribeCamera(const std::string& base_topic, uint32_t queue_size,
00140                                    void(T::*fp)(const sensor_msgs::ImageConstPtr&,
00141                                                 const sensor_msgs::CameraInfoConstPtr&),
00142                                    const boost::shared_ptr<T>& obj,
00143                                    const TransportHints& transport_hints = TransportHints())
00144   {
00145     return subscribeCamera(base_topic, queue_size, boost::bind(fp, obj.get(), _1, _2), obj,
00146                            transport_hints);
00147   }
00148 
00153   std::vector<std::string> getDeclaredTransports() const;
00154 
00158   std::vector<std::string> getLoadableTransports() const;
00159 
00160 private:
00161   struct Impl;
00162   typedef boost::shared_ptr<Impl> ImplPtr;
00163   typedef boost::weak_ptr<Impl> ImplWPtr;
00164 
00165   ImplPtr impl_;
00166 };
00167 
00168 } //namespace image_transport
00169 
00170 #endif


image_transport
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:08