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 #include <image_transport/simple_publisher_plugin.h>
00036 #include <cv_bridge/cv_bridge.h>
00037 #include <std_msgs/Header.h>
00038 #include <dynamic_reconfigure/server.h>
00039 #include <theora_image_transport/TheoraPublisherConfig.h>
00040 #include <theora_image_transport/Packet.h>
00041
00042 #include <theora/codec.h>
00043 #include <theora/theoraenc.h>
00044 #include <theora/theoradec.h>
00045
00046 namespace theora_image_transport {
00047
00048 class TheoraPublisher : public image_transport::SimplePublisherPlugin<theora_image_transport::Packet>
00049 {
00050 public:
00051 TheoraPublisher();
00052
00053 ~TheoraPublisher();
00054
00055
00056 virtual std::string getTransportName() const { return "theora"; }
00057
00058 protected:
00059
00060 virtual void advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size,
00061 const image_transport::SubscriberStatusCallback &user_connect_cb,
00062 const image_transport::SubscriberStatusCallback &user_disconnect_cb,
00063 const ros::VoidPtr &tracked_object, bool latch);
00064
00065
00066 virtual void connectCallback(const ros::SingleSubscriberPublisher& pub);
00067
00068
00069 virtual void publish(const sensor_msgs::Image& message,
00070 const PublishFn& publish_fn) const;
00071
00072
00073 typedef theora_image_transport::TheoraPublisherConfig Config;
00074 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00075 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00076
00077 void configCb(Config& config, uint32_t level);
00078
00079
00080 bool ensureEncodingContext(const sensor_msgs::Image& image, const PublishFn& publish_fn) const;
00081 void oggPacketToMsg(const std_msgs::Header& header, const ogg_packet &oggpacket,
00082 theora_image_transport::Packet &msg) const;
00083 void updateKeyframeFrequency() const;
00084
00085
00086
00087 mutable cv_bridge::CvImage img_image_;
00088 mutable th_info encoder_setup_;
00089 mutable ogg_uint32_t keyframe_frequency_;
00090 mutable boost::shared_ptr<th_enc_ctx> encoding_context_;
00091 mutable std::vector<theora_image_transport::Packet> stream_header_;
00092 };
00093
00094 }