libav_streamer.h
Go to the documentation of this file.
00001 #ifndef LIBAV_STREAMERS_H_
00002 #define LIBAV_STREAMERS_H_
00003 
00004 #include <image_transport/image_transport.h>
00005 #include "web_video_server/image_streamer.h"
00006 #include "async_web_server_cpp/http_request.hpp"
00007 #include "async_web_server_cpp/http_connection.hpp"
00008 
00009 extern "C"
00010 {
00011 #include <libavcodec/avcodec.h>
00012 #include <libavformat/avformat.h>
00013 #include <libavutil/intreadwrite.h>
00014 #include <libavformat/avio.h>
00015 #include <libswscale/swscale.h>
00016 #include <libavutil/opt.h>
00017 #include <libavutil/mathematics.h>
00018 }
00019 
00020 namespace web_video_server
00021 {
00022 
00023 class LibavStreamer : public ImageTransportImageStreamer
00024 {
00025 public:
00026   LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
00027                 ros::NodeHandle& nh, const std::string &format_name, const std::string &codec_name,
00028                 const std::string &content_type);
00029 
00030   ~LibavStreamer();
00031 
00032 protected:
00033   virtual void initializeEncoder();
00034   virtual void sendImage(const cv::Mat&, const ros::Time& time);
00035   virtual void initialize(const cv::Mat&);
00036   AVOutputFormat* output_format_;
00037   AVFormatContext* format_context_;
00038   AVCodec* codec_;
00039   AVCodecContext* codec_context_;
00040   AVStream* video_stream_;
00041 
00042 private:
00043   AVFrame* frame_;
00044   AVPicture* picture_;
00045   AVPicture* tmp_picture_;
00046   struct SwsContext* sws_context_;
00047   ros::Time first_image_timestamp_;
00048   boost::mutex encode_mutex_;
00049 
00050   std::string format_name_;
00051   std::string codec_name_;
00052   std::string content_type_;
00053   int bitrate_;
00054   int qmin_;
00055   int qmax_;
00056   int gop_;
00057 };
00058 
00059 class LibavStreamerType : public ImageStreamerType
00060 {
00061 public:
00062   LibavStreamerType(const std::string &format_name, const std::string &codec_name, const std::string &content_type);
00063 
00064   boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
00065                                                    async_web_server_cpp::HttpConnectionPtr connection,
00066                                                    ros::NodeHandle& nh);
00067 
00068   std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
00069 
00070 private:
00071   const std::string format_name_;
00072   const std::string codec_name_;
00073   const std::string content_type_;
00074 };
00075 
00076 }
00077 
00078 #endif


web_video_server
Author(s): Mitchell Wills
autogenerated on Thu Aug 27 2015 15:42:12