35 #ifndef IMAGE_TRANSPORT_CAMERA_PUBLISHER_H 36 #define IMAGE_TRANSPORT_CAMERA_PUBLISHER_H 39 #include <sensor_msgs/Image.h> 40 #include <sensor_msgs/CameraInfo.h> 74 uint32_t getNumSubscribers()
const;
79 std::string getTopic()
const;
84 std::string getInfoTopic()
const;
89 void publish(
const sensor_msgs::Image& image,
const sensor_msgs::CameraInfo& info)
const;
94 void publish(
const sensor_msgs::ImageConstPtr& image,
95 const sensor_msgs::CameraInfoConstPtr& info)
const;
104 void publish(sensor_msgs::Image& image, sensor_msgs::CameraInfo& info,
ros::Time stamp)
const;
111 operator void*()
const;
118 const std::string& base_topic, uint32_t queue_size,
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Manages advertisements for publishing camera images.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< Impl > ImplPtr
bool operator==(const CameraPublisher &rhs) const
bool operator!=(const CameraPublisher &rhs) const
#define IMAGE_TRANSPORT_DECL
boost::weak_ptr< Impl > ImplWPtr
Advertise and subscribe to image topics.