00001 #ifndef IMAGE_TRANSPORT_CAMERA_SUBSCRIBER_H 00002 #define IMAGE_TRANSPORT_CAMERA_SUBSCRIBER_H 00003 00004 #include <ros/ros.h> 00005 #include <sensor_msgs/CameraInfo.h> 00006 #include <sensor_msgs/Image.h> 00007 #include "image_transport/transport_hints.h" 00008 00009 namespace image_transport { 00010 00011 class ImageTransport; 00012 00028 class CameraSubscriber 00029 { 00030 public: 00031 typedef boost::function<void(const sensor_msgs::ImageConstPtr&, 00032 const sensor_msgs::CameraInfoConstPtr&)> Callback; 00033 00034 CameraSubscriber() {} 00035 00039 std::string getTopic() const; 00040 00044 std::string getInfoTopic() const; 00045 00049 uint32_t getNumPublishers() const; 00050 00054 std::string getTransport() const; 00055 00059 void shutdown(); 00060 00061 operator void*() const; 00062 bool operator< (const CameraSubscriber& rhs) const { return impl_ < rhs.impl_; } 00063 bool operator!=(const CameraSubscriber& rhs) const { return impl_ != rhs.impl_; } 00064 bool operator==(const CameraSubscriber& rhs) const { return impl_ == rhs.impl_; } 00065 00066 private: 00067 CameraSubscriber(ImageTransport& image_it, ros::NodeHandle& info_nh, 00068 const std::string& base_topic, uint32_t queue_size, 00069 const Callback& callback, 00070 const ros::VoidPtr& tracked_object = ros::VoidPtr(), 00071 const TransportHints& transport_hints = TransportHints()); 00072 00073 struct Impl; 00074 typedef boost::shared_ptr<Impl> ImplPtr; 00075 typedef boost::weak_ptr<Impl> ImplWPtr; 00076 00077 ImplPtr impl_; 00078 00079 friend class ImageTransport; 00080 }; 00081 00082 } //namespace image_transport 00083 00084 #endif