00001 #ifndef IMAGEM_TRANSPORT_THEORA_PUBLISHER_H
00002 #define IMAGEM_TRANSPORT_THEORA_PUBLISHER_H
00003
00004 #include <message_transport/simple_publisher_plugin.h>
00005 #include <sensor_msgs/Image.h>
00006 #include <opencv/cv.h>
00007 #include <opencv/cxcore.h>
00008 #include <cv_bridge/CvBridge.h>
00009 #include <theora_imagem_transport/packet.h>
00010
00011 #include <theora/codec.h>
00012 #include <theora/theoraenc.h>
00013 #include <theora/theoradec.h>
00014
00015 namespace theora_imagem_transport {
00016
00017 class TheoraPublisher : public message_transport::SimplePublisherPlugin<sensor_msgs::Image,theora_imagem_transport::packet>
00018 {
00019 public:
00020 TheoraPublisher();
00021 virtual ~TheoraPublisher();
00022
00023
00024 virtual std::string getTransportName() const
00025 {
00026 return "theora";
00027 }
00028
00029 protected:
00030
00031 virtual void connectCallback(const ros::SingleSubscriberPublisher& pub);
00032
00033
00034 virtual void publish(const sensor_msgs::Image& message,
00035 const message_transport::SimplePublisherPlugin<sensor_msgs::Image,theora_imagem_transport::packet>::PublishFn& publish_fn) const ;
00036
00037 private:
00038
00039 void sendHeader(const ros::SingleSubscriberPublisher& pub) const;
00040 void ensure_encoding_context(const CvSize &size, const PublishFn& publish_fn) const;
00041 void oggPacketToMsg(const ogg_packet &oggpacket, theora_imagem_transport::packet &msgOutput) const;
00042
00043
00044
00045
00046
00047
00048 mutable sensor_msgs::CvBridge img_bridge_;
00049 mutable th_enc_ctx* encoding_context_;
00050 mutable std::vector<ogg_packet> stream_header_;
00051
00052
00053 mutable int nearestWidth;
00054 mutable int nearestHeight;
00055 mutable int nearestXoff;
00056 mutable int nearestYoff;
00057 };
00058
00059 }
00060
00061 #endif // IMAGEM_TRANSPORT_THEORA_PUBLISHER_H