Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef IMAGE_TRANSPORT_CAMERA_PUBLISHER_H
00036 #define IMAGE_TRANSPORT_CAMERA_PUBLISHER_H
00037
00038 #include <ros/ros.h>
00039 #include <sensor_msgs/Image.h>
00040 #include <sensor_msgs/CameraInfo.h>
00041 #include "image_transport/single_subscriber_publisher.h"
00042
00043 namespace image_transport {
00044
00045 class ImageTransport;
00046
00062 class CameraPublisher
00063 {
00064 public:
00065 CameraPublisher() {}
00066
00073 uint32_t getNumSubscribers() const;
00074
00078 std::string getTopic() const;
00079
00083 std::string getInfoTopic() const;
00084
00088 void publish(const sensor_msgs::Image& image, const sensor_msgs::CameraInfo& info) const;
00089
00093 void publish(const sensor_msgs::ImageConstPtr& image,
00094 const sensor_msgs::CameraInfoConstPtr& info) const;
00095
00103 void publish(sensor_msgs::Image& image, sensor_msgs::CameraInfo& info, ros::Time stamp) const;
00104
00108 void shutdown();
00109
00110 operator void*() const;
00111 bool operator< (const CameraPublisher& rhs) const { return impl_ < rhs.impl_; }
00112 bool operator!=(const CameraPublisher& rhs) const { return impl_ != rhs.impl_; }
00113 bool operator==(const CameraPublisher& rhs) const { return impl_ == rhs.impl_; }
00114
00115 private:
00116 CameraPublisher(ImageTransport& image_it, ros::NodeHandle& info_nh,
00117 const std::string& base_topic, uint32_t queue_size,
00118 const SubscriberStatusCallback& image_connect_cb,
00119 const SubscriberStatusCallback& image_disconnect_cb,
00120 const ros::SubscriberStatusCallback& info_connect_cb,
00121 const ros::SubscriberStatusCallback& info_disconnect_cb,
00122 const ros::VoidPtr& tracked_object, bool latch);
00123
00124 struct Impl;
00125 typedef boost::shared_ptr<Impl> ImplPtr;
00126 typedef boost::weak_ptr<Impl> ImplWPtr;
00127
00128 ImplPtr impl_;
00129
00130 friend class ImageTransport;
00131 };
00132
00133 }
00134
00135 #endif