35 #ifndef IMAGE_TRANSPORT_CAMERA_SUBSCRIBER_H 36 #define IMAGE_TRANSPORT_CAMERA_SUBSCRIBER_H 39 #include <sensor_msgs/CameraInfo.h> 40 #include <sensor_msgs/Image.h> 66 typedef boost::function<void(
const sensor_msgs::ImageConstPtr&,
67 const sensor_msgs::CameraInfoConstPtr&)>
Callback;
74 std::string getTopic()
const;
79 std::string getInfoTopic()
const;
84 uint32_t getNumPublishers()
const;
89 std::string getTransport()
const;
96 operator void*()
const;
103 const std::string& base_topic, uint32_t queue_size,
104 const Callback& callback,
Manages a subscription callback on synchronized Image and CameraInfo topics.
boost::weak_ptr< Impl > ImplWPtr
boost::shared_ptr< Impl > ImplPtr
#define IMAGE_TRANSPORT_DECL
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Stores transport settings for an image topic subscription.
ROSCONSOLE_DECL void shutdown()
Advertise and subscribe to image topics.
bool operator==(const CameraSubscriber &rhs) const
bool operator!=(const CameraSubscriber &rhs) const