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> 88 void publish(
const sensor_msgs::Image& image,
const sensor_msgs::CameraInfo& info)
const;
93 void publish(
const sensor_msgs::ImageConstPtr& image,
94 const sensor_msgs::CameraInfoConstPtr& info)
const;
103 void publish(sensor_msgs::Image& image, sensor_msgs::CameraInfo& info,
ros::Time stamp)
const;
110 operator void*()
const;
117 const std::string& base_topic, uint32_t queue_size,
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
Publish an (image, info) pair on the topics associated with this CameraPublisher. ...
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::string getInfoTopic() const
Returns the camera info topic of this CameraPublisher.
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this CameraPublisher.
Manages advertisements for publishing camera images.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< Impl > ImplPtr
bool operator==(const CameraPublisher &rhs) const
void shutdown()
Shutdown the advertisements associated with this Publisher.
bool operator!=(const CameraPublisher &rhs) const
bool operator<(const CameraPublisher &rhs) const
boost::weak_ptr< Impl > ImplWPtr
Advertise and subscribe to image topics.
std::string getTopic() const
Returns the base (image) topic of this CameraPublisher.