diff --git a/CMakeLists.txt b/CMakeLists.txt index c25f1ac..72f9f2f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -43,6 +43,8 @@ add_executable(${PROJECT_NAME} src/image_streamer.cpp src/libav_streamer.cpp src/vp8_streamer.cpp + src/h264_streamer.cpp + src/vp9_streamer.cpp src/multipart_stream.cpp src/ros_compressed_streamer.cpp src/jpeg_streamers.cpp) diff --git a/include/web_video_server/h264_streamer.h b/include/web_video_server/h264_streamer.h new file mode 100644 index 0000000..28c67f2 --- /dev/null +++ b/include/web_video_server/h264_streamer.h @@ -0,0 +1,35 @@ +#ifndef H264_STREAMERS_H_ +#define H264_STREAMERS_H_ + +#include +#include "web_video_server/libav_streamer.h" +#include "async_web_server_cpp/http_request.hpp" +#include "async_web_server_cpp/http_connection.hpp" + +namespace web_video_server +{ + +class H264Streamer : public LibavStreamer +{ +public: + H264Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + ~H264Streamer(); +protected: + virtual void initializeEncoder(); + std::string preset_; +}; + +class H264StreamerType : public LibavStreamerType +{ +public: + H264StreamerType(); + virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); +}; + +} + +#endif + diff --git a/include/web_video_server/libav_streamer.h b/include/web_video_server/libav_streamer.h index 206d7ad..e8dc12a 100644 --- a/include/web_video_server/libav_streamer.h +++ b/include/web_video_server/libav_streamer.h @@ -40,6 +40,8 @@ class LibavStreamer : public ImageTransportImageStreamer AVCodecContext* codec_context_; AVStream* video_stream_; + AVDictionary* opt_; // container format options + private: AVFrame* frame_; struct SwsContext* sws_context_; @@ -53,6 +55,8 @@ class LibavStreamer : public ImageTransportImageStreamer int qmin_; int qmax_; int gop_; + + uint8_t* io_buffer_; // custom IO buffer }; class LibavStreamerType : public ImageStreamerType diff --git a/include/web_video_server/vp9_streamer.h b/include/web_video_server/vp9_streamer.h new file mode 100644 index 0000000..041f466 --- /dev/null +++ b/include/web_video_server/vp9_streamer.h @@ -0,0 +1,33 @@ +#ifndef VP9_STREAMERS_H_ +#define VP9_STREAMERS_H_ + +#include +#include "web_video_server/libav_streamer.h" +#include "async_web_server_cpp/http_request.hpp" +#include "async_web_server_cpp/http_connection.hpp" + +namespace web_video_server +{ + +class Vp9Streamer : public LibavStreamer +{ +public: + Vp9Streamer(const async_web_server_cpp::HttpRequest& request, async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); + ~Vp9Streamer(); +protected: + virtual void initializeEncoder(); +}; + +class Vp9StreamerType : public LibavStreamerType +{ +public: + Vp9StreamerType(); + virtual boost::shared_ptr create_streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh); +}; + +} + +#endif diff --git a/src/h264_streamer.cpp b/src/h264_streamer.cpp new file mode 100644 index 0000000..5477369 --- /dev/null +++ b/src/h264_streamer.cpp @@ -0,0 +1,49 @@ +#include "web_video_server/h264_streamer.h" + +namespace web_video_server +{ + +H264Streamer::H264Streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + LibavStreamer(request, connection, nh, "mp4", "libx264", "video/mp4") +{ + /* possible quality presets: + * ultrafast, superfast, veryfast, faster, fast, medium, slow, slower, veryslow, placebo + * no latency improvements observed with ultrafast instead of medium + */ + preset_ = request.get_query_param_value_or_default("preset", "ultrafast"); +} + +H264Streamer::~H264Streamer() +{ +} + +void H264Streamer::initializeEncoder() +{ + av_opt_set(codec_context_->priv_data, "preset", preset_.c_str(), 0); + av_opt_set(codec_context_->priv_data, "tune", "zerolatency", 0); + av_opt_set_int(codec_context_->priv_data, "crf", 20, 0); + av_opt_set_int(codec_context_->priv_data, "bufsize", 100, 0); + av_opt_set_int(codec_context_->priv_data, "keyint", 30, 0); + av_opt_set_int(codec_context_->priv_data, "g", 1, 0); + + // container format options + if (!strcmp(format_context_->oformat->name, "mp4")) { + // set up mp4 for streaming (instead of seekable file output) + av_dict_set(&opt_, "movflags", "+frag_keyframe+empty_moov+faststart", 0); + } +} + +H264StreamerType::H264StreamerType() : + LibavStreamerType("mp4", "libx264", "video/mp4") +{ +} + +boost::shared_ptr H264StreamerType::create_streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh) +{ + return boost::shared_ptr(new H264Streamer(request, connection, nh)); +} + +} diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index fc733b1..08980e4 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -50,7 +50,7 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, const std::string &content_type) : ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( 0), frame_(0), sws_context_(0), first_image_timestamp_(0), format_name_( - format_name), codec_name_(codec_name), content_type_(content_type) + format_name), codec_name_(codec_name), content_type_(content_type), opt_(0), io_buffer_(0) { bitrate_ = request.get_query_param_value_or_default("bitrate", 100000); @@ -75,12 +75,26 @@ LibavStreamer::~LibavStreamer() av_frame_free(&frame_); #endif } + if (io_buffer_) + delete io_buffer_; + if (format_context_->pb) + av_free(format_context_->pb); if (format_context_) avformat_free_context(format_context_); if (sws_context_) sws_freeContext(sws_context_); } +// output callback for ffmpeg IO context +static int dispatch_output_packet(void* opaque, uint8_t* buffer, int buffer_size) +{ + async_web_server_cpp::HttpConnectionPtr connection = *((async_web_server_cpp::HttpConnectionPtr*) opaque); + std::vector encoded_frame; + encoded_frame.assign(buffer, buffer + buffer_size); + connection->write_and_clear(encoded_frame); + return 0; // TODO: can this fail? +} + void LibavStreamer::initialize(const cv::Mat &img) { // Load format @@ -102,6 +116,22 @@ void LibavStreamer::initialize(const cv::Mat &img) } format_context_->oformat = output_format_; + // Set up custom IO callback. + size_t io_buffer_size = 3 * 1024; // 3M seen elsewhere and adjudged good + io_buffer_ = new unsigned char[io_buffer_size]; + AVIOContext* io_ctx = avio_alloc_context(io_buffer_, io_buffer_size, AVIO_FLAG_WRITE, &connection_, NULL, dispatch_output_packet, NULL); + if (!io_ctx) + { + async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, + connection_, + NULL, NULL); + throw std::runtime_error("Error setting up IO context"); + } + io_ctx->seekable = 0; // no seeking, it's a stream + format_context_->pb = io_ctx; + output_format_->flags |= AVFMT_FLAG_CUSTOM_IO; + output_format_->flags |= AVFMT_NOFILE; + // Load codec if (codec_name_.empty()) // use default codec if none specified codec_ = avcodec_find_encoder(output_format_->video_codec); @@ -127,7 +157,7 @@ void LibavStreamer::initialize(const cv::Mat &img) // Set options avcodec_get_context_defaults3(codec_context_, codec_); - codec_context_->codec_id = output_format_->video_codec; + codec_context_->codec_id = codec_->id; codec_context_->bit_rate = bitrate_; codec_context_->width = output_width_; @@ -171,7 +201,9 @@ void LibavStreamer::initialize(const cv::Mat &img) av_image_alloc(frame_->data, frame_->linesize, output_width_, output_height_, codec_context_->pix_fmt, 1); - + frame_->width = output_width_; + frame_->height = output_height_; + frame_->format = codec_context_->pix_fmt; output_format_->flags |= AVFMT_NOFILE; // Generate header @@ -182,24 +214,6 @@ void LibavStreamer::initialize(const cv::Mat &img) av_dict_set(&format_context_->metadata, "author", "ROS web_video_server", 0); av_dict_set(&format_context_->metadata, "title", topic_.c_str(), 0); - if (avio_open_dyn_buf(&format_context_->pb) >= 0) - { - if (avformat_write_header(format_context_, NULL) < 0) - { - async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, - connection_, - NULL, NULL); - throw std::runtime_error("Error openning dynamic buffer"); - } - header_size = avio_close_dyn_buf(format_context_->pb, &header_raw_buffer); - - // copy header buffer to vector - header_buffer.resize(header_size); - memcpy(&header_buffer[0], header_raw_buffer, header_size); - - av_free(header_raw_buffer); - } - // Send response headers async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header( "Server", "web_video_server").header("Cache-Control", @@ -208,7 +222,13 @@ void LibavStreamer::initialize(const cv::Mat &img) "Content-type", content_type_).header("Access-Control-Allow-Origin", "*").write(connection_); // Send video stream header - connection_->write_and_clear(header_buffer); + if (avformat_write_header(format_context_, &opt_) < 0) + { + async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, + connection_, + NULL, NULL); + throw std::runtime_error("Error openning dynamic buffer"); + } } void LibavStreamer::initializeEncoder() @@ -235,7 +255,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) #else AVFrame *raw_frame = av_frame_alloc(); av_image_fill_arrays(raw_frame->data, raw_frame->linesize, - img.data, input_coding_format, output_width_, output_height_, 0); + img.data, input_coding_format, output_width_, output_height_, 1); #endif @@ -310,18 +330,9 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time) pkt.stream_index = video_stream_->index; - if (avio_open_dyn_buf(&format_context_->pb) >= 0) + if (av_write_frame(format_context_, &pkt)) { - if (av_write_frame(format_context_, &pkt)) - { - throw std::runtime_error("Error when writing frame"); - } - size = avio_close_dyn_buf(format_context_->pb, &output_buf); - - encoded_frame.resize(size); - memcpy(&encoded_frame[0], output_buf, size); - - av_free(output_buf); + throw std::runtime_error("Error when writing frame"); } } else diff --git a/src/vp9_streamer.cpp b/src/vp9_streamer.cpp new file mode 100644 index 0000000..b487092 --- /dev/null +++ b/src/vp9_streamer.cpp @@ -0,0 +1,38 @@ +#include "web_video_server/vp9_streamer.h" + +namespace web_video_server +{ + +Vp9Streamer::Vp9Streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh) : + LibavStreamer(request, connection, nh, "webm", "libvpx-vp9", "video/webm") +{ +} +Vp9Streamer::~Vp9Streamer() +{ +} + +void Vp9Streamer::initializeEncoder() +{ + + // codec options set up to provide somehow reasonable performance in cost of poor quality + // should be updated as soon as VP9 encoding matures + av_opt_set_int(codec_context_->priv_data, "pass", 1, 0); + av_opt_set_int(codec_context_->priv_data, "speed", 8, 0); + av_opt_set_int(codec_context_->priv_data, "cpu-used", 4, 0); // 8 is max + av_opt_set_int(codec_context_->priv_data, "crf", 20, 0); // 0..63 (higher is lower quality) +} + +Vp9StreamerType::Vp9StreamerType() : + LibavStreamerType("webm", "libvpx-vp9", "video/webm") +{ +} + +boost::shared_ptr Vp9StreamerType::create_streamer(const async_web_server_cpp::HttpRequest& request, + async_web_server_cpp::HttpConnectionPtr connection, + ros::NodeHandle& nh) +{ + return boost::shared_ptr(new Vp9Streamer(request, connection, nh)); +} + +} diff --git a/src/web_video_server.cpp b/src/web_video_server.cpp index 504bb1f..75c81bf 100644 --- a/src/web_video_server.cpp +++ b/src/web_video_server.cpp @@ -9,6 +9,8 @@ #include "web_video_server/ros_compressed_streamer.h" #include "web_video_server/jpeg_streamers.h" #include "web_video_server/vp8_streamer.h" +#include "web_video_server/h264_streamer.h" +#include "web_video_server/vp9_streamer.h" #include "async_web_server_cpp/http_reply.hpp" namespace web_video_server @@ -57,6 +59,8 @@ WebVideoServer::WebVideoServer(ros::NodeHandle &nh, ros::NodeHandle &private_nh) stream_types_["mjpeg"] = boost::shared_ptr(new MjpegStreamerType()); stream_types_["ros_compressed"] = boost::shared_ptr(new RosCompressedStreamerType()); stream_types_["vp8"] = boost::shared_ptr(new Vp8StreamerType()); + stream_types_["h264"] = boost::shared_ptr(new H264StreamerType()); + stream_types_["vp9"] = boost::shared_ptr(new Vp9StreamerType()); handler_group_.addHandlerForPath("/", boost::bind(&WebVideoServer::handle_list_streams, this, _1, _2, _3, _4)); handler_group_.addHandlerForPath("/stream", boost::bind(&WebVideoServer::handle_stream, this, _1, _2, _3, _4));