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> 65 typedef boost::function<void(
const sensor_msgs::ImageConstPtr&,
66 const sensor_msgs::CameraInfoConstPtr&)>
Callback;
95 operator void*()
const;
102 const std::string& base_topic, uint32_t queue_size,
103 const Callback& callback,
std::string getInfoTopic() const
Get the camera info topic.
Manages a subscription callback on synchronized Image and CameraInfo topics.
bool operator<(const CameraSubscriber &rhs) const
boost::weak_ptr< Impl > ImplWPtr
std::string getTransport() const
Returns the name of the transport being used.
bool operator==(const CameraSubscriber &rhs) const
boost::shared_ptr< Impl > ImplPtr
bool operator!=(const CameraSubscriber &rhs) const
void shutdown()
Unsubscribe the callback associated with this CameraSubscriber.
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Stores transport settings for an image topic subscription.
uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
Advertise and subscribe to image topics.
std::string getTopic() const
Get the base topic (on which the raw image is published).