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 #include <libavutil/imgutils.h>
00019 }
00020
00021 namespace web_video_server
00022 {
00023
00024 class LibavStreamer : public ImageTransportImageStreamer
00025 {
00026 public:
00027 LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection,
00028 ros::NodeHandle& nh, const std::string &format_name, const std::string &codec_name,
00029 const std::string &content_type);
00030
00031 ~LibavStreamer();
00032
00033 protected:
00034 virtual void initializeEncoder();
00035 virtual void sendImage(const cv::Mat&, const ros::Time& time);
00036 virtual void initialize(const cv::Mat&);
00037 AVOutputFormat* output_format_;
00038 AVFormatContext* format_context_;
00039 AVCodec* codec_;
00040 AVCodecContext* codec_context_;
00041 AVStream* video_stream_;
00042
00043 AVDictionary* opt_;
00044
00045 private:
00046 AVFrame* frame_;
00047 struct SwsContext* sws_context_;
00048 ros::Time first_image_timestamp_;
00049 boost::mutex encode_mutex_;
00050
00051 std::string format_name_;
00052 std::string codec_name_;
00053 std::string content_type_;
00054 int bitrate_;
00055 int qmin_;
00056 int qmax_;
00057 int gop_;
00058
00059 uint8_t* io_buffer_;
00060 };
00061
00062 class LibavStreamerType : public ImageStreamerType
00063 {
00064 public:
00065 LibavStreamerType(const std::string &format_name, const std::string &codec_name, const std::string &content_type);
00066
00067 boost::shared_ptr<ImageStreamer> create_streamer(const async_web_server_cpp::HttpRequest &request,
00068 async_web_server_cpp::HttpConnectionPtr connection,
00069 ros::NodeHandle& nh);
00070
00071 std::string create_viewer(const async_web_server_cpp::HttpRequest &request);
00072
00073 private:
00074 const std::string format_name_;
00075 const std::string codec_name_;
00076 const std::string content_type_;
00077 };
00078
00079 }
00080
00081 #endif