Go to the documentation of this file.00001 #include <image_transport/simple_publisher_plugin.h>
00002 #include <opencv/cv.h>
00003 #include <opencv/cxcore.h>
00004 #include <cv_bridge/cv_bridge.h>
00005 #include <std_msgs/Header.h>
00006 #include <dynamic_reconfigure/server.h>
00007 #include <theora_image_transport/TheoraPublisherConfig.h>
00008 #include <theora_image_transport/Packet.h>
00009
00010 #include <theora/codec.h>
00011 #include <theora/theoraenc.h>
00012 #include <theora/theoradec.h>
00013
00014 namespace theora_image_transport {
00015
00016 class TheoraPublisher : public image_transport::SimplePublisherPlugin<theora_image_transport::Packet>
00017 {
00018 public:
00019 TheoraPublisher();
00020
00021 ~TheoraPublisher();
00022
00023
00024 virtual std::string getTransportName() const { return "theora"; }
00025
00026 protected:
00027
00028 virtual void advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00029 const image_transport::SubscriberStatusCallback &user_connect_cb,
00030 const image_transport::SubscriberStatusCallback &user_disconnect_cb,
00031 const ros::VoidPtr &tracked_object, bool latch);
00032
00033
00034 virtual void connectCallback(const ros::SingleSubscriberPublisher& pub);
00035
00036
00037 virtual void publish(const sensor_msgs::Image& message,
00038 const PublishFn& publish_fn) const;
00039
00040
00041 typedef theora_image_transport::TheoraPublisherConfig Config;
00042 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00043 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00044
00045 void configCb(Config& config, uint32_t level);
00046
00047
00048 bool ensureEncodingContext(const sensor_msgs::Image& image, const PublishFn& publish_fn) const;
00049 void oggPacketToMsg(const std_msgs::Header& header, const ogg_packet &oggpacket,
00050 theora_image_transport::Packet &msg) const;
00051 void updateKeyframeFrequency() const;
00052
00053
00054
00055 mutable cv_bridge::CvImage img_image_;
00056 mutable th_info encoder_setup_;
00057 mutable ogg_uint32_t keyframe_frequency_;
00058 mutable boost::shared_ptr<th_enc_ctx> encoding_context_;
00059 mutable std::vector<theora_image_transport::Packet> stream_header_;
00060 };
00061
00062 }