00001 #include "web_video_server/libav_streamer.h"
00002 #include "async_web_server_cpp/http_reply.hpp"
00003
00004 namespace web_video_server
00005 {
00006
00007 static int ffmpeg_boost_mutex_lock_manager(void **mutex, enum AVLockOp op)
00008 {
00009 if (NULL == mutex)
00010 return -1;
00011
00012 switch (op)
00013 {
00014 case AV_LOCK_CREATE:
00015 {
00016 *mutex = NULL;
00017 boost::mutex *m = new boost::mutex();
00018 *mutex = static_cast<void *>(m);
00019 break;
00020 }
00021 case AV_LOCK_OBTAIN:
00022 {
00023 boost::mutex *m = static_cast<boost::mutex *>(*mutex);
00024 m->lock();
00025 break;
00026 }
00027 case AV_LOCK_RELEASE:
00028 {
00029 boost::mutex *m = static_cast<boost::mutex *>(*mutex);
00030 m->unlock();
00031 break;
00032 }
00033 case AV_LOCK_DESTROY:
00034 {
00035 boost::mutex *m = static_cast<boost::mutex *>(*mutex);
00036 m->lock();
00037 m->unlock();
00038 delete m;
00039 break;
00040 }
00041 default:
00042 break;
00043 }
00044 return 0;
00045 }
00046
00047 LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request,
00048 async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh,
00049 const std::string &format_name, const std::string &codec_name,
00050 const std::string &content_type) :
00051 ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_(
00052 0), frame_(0), picture_(0), tmp_picture_(0), sws_context_(0), first_image_timestamp_(0), format_name_(
00053 format_name), codec_name_(codec_name), content_type_(content_type)
00054 {
00055
00056 bitrate_ = request.get_query_param_value_or_default<int>("bitrate", 100000);
00057 qmin_ = request.get_query_param_value_or_default<int>("qmin", 10);
00058 qmax_ = request.get_query_param_value_or_default<int>("qmax", 42);
00059 gop_ = request.get_query_param_value_or_default<int>("gop", 250);
00060
00061 av_lockmgr_register(&ffmpeg_boost_mutex_lock_manager);
00062 av_register_all();
00063 }
00064
00065 LibavStreamer::~LibavStreamer()
00066 {
00067 if (codec_context_)
00068 avcodec_close(codec_context_);
00069 if (frame_)
00070 {
00071 #if (LIBAVCODEC_VERSION_MAJOR < 54)
00072 av_free(frame_);
00073 frame_ = NULL;
00074 #else
00075 avcodec_free_frame(&frame_);
00076 #endif
00077 }
00078 if (format_context_)
00079 avformat_free_context(format_context_);
00080 if (picture_)
00081 {
00082 avpicture_free(picture_);
00083 delete picture_;
00084 picture_ = NULL;
00085 }
00086 if (tmp_picture_)
00087 {
00088 delete tmp_picture_;
00089 tmp_picture_ = NULL;
00090 }
00091 if (sws_context_)
00092 sws_freeContext(sws_context_);
00093 }
00094
00095 void LibavStreamer::initialize(const cv::Mat &img)
00096 {
00097
00098 format_context_ = avformat_alloc_context();
00099 if (!format_context_)
00100 {
00101 async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
00102 connection_,
00103 NULL, NULL);
00104 throw std::runtime_error("Error allocating ffmpeg format context");
00105 }
00106 output_format_ = av_guess_format(format_name_.c_str(), NULL, NULL);
00107 if (!output_format_)
00108 {
00109 async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
00110 connection_,
00111 NULL, NULL);
00112 throw std::runtime_error("Error looking up output format");
00113 }
00114 format_context_->oformat = output_format_;
00115
00116
00117 if (codec_name_.empty())
00118 codec_ = avcodec_find_encoder(output_format_->video_codec);
00119 else
00120 codec_ = avcodec_find_encoder_by_name(codec_name_.c_str());
00121 if (!codec_)
00122 {
00123 async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
00124 connection_,
00125 NULL, NULL);
00126 throw std::runtime_error("Error looking up codec");
00127 }
00128 video_stream_ = avformat_new_stream(format_context_, codec_);
00129 if (!video_stream_)
00130 {
00131 async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
00132 connection_,
00133 NULL, NULL);
00134 throw std::runtime_error("Error creating video stream");
00135 }
00136 codec_context_ = video_stream_->codec;
00137
00138
00139 avcodec_get_context_defaults3(codec_context_, codec_);
00140
00141 codec_context_->codec_id = output_format_->video_codec;
00142 codec_context_->bit_rate = bitrate_;
00143
00144 codec_context_->width = output_width_;
00145 codec_context_->height = output_height_;
00146 codec_context_->delay = 0;
00147
00148 video_stream_->time_base.num = 1;
00149 video_stream_->time_base.den = 1000;
00150
00151 codec_context_->time_base.num = 1;
00152 codec_context_->time_base.den = 1;
00153 codec_context_->gop_size = gop_;
00154 codec_context_->pix_fmt = PIX_FMT_YUV420P;
00155 codec_context_->max_b_frames = 0;
00156
00157
00158 codec_context_->qmin = qmin_;
00159 codec_context_->qmax = qmax_;
00160
00161 initializeEncoder();
00162
00163
00164 if (format_context_->oformat->flags & AVFMT_GLOBALHEADER)
00165 codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER;
00166
00167
00168 if (avcodec_open2(codec_context_, codec_, NULL) < 0)
00169 {
00170 async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
00171 connection_,
00172 NULL, NULL);
00173 throw std::runtime_error("Could not open video codec");
00174 }
00175
00176
00177 frame_ = avcodec_alloc_frame();
00178 tmp_picture_ = new AVPicture;
00179 picture_ = new AVPicture;
00180 int ret = avpicture_alloc(picture_, codec_context_->pix_fmt, output_width_, output_height_);
00181 if (ret < 0)
00182 {
00183 async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
00184 connection_,
00185 NULL, NULL);
00186 throw std::runtime_error("Could not allocate picture frame");
00187 }
00188 *((AVPicture *)frame_) = *picture_;
00189
00190 output_format_->flags |= AVFMT_NOFILE;
00191
00192
00193 std::vector<uint8_t> header_buffer;
00194 std::size_t header_size;
00195 uint8_t *header_raw_buffer;
00196
00197 av_dict_set(&format_context_->metadata, "author", "ROS web_video_server", 0);
00198 av_dict_set(&format_context_->metadata, "title", topic_.c_str(), 0);
00199
00200 if (avio_open_dyn_buf(&format_context_->pb) >= 0)
00201 {
00202 if (avformat_write_header(format_context_, NULL) < 0)
00203 {
00204 async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
00205 connection_,
00206 NULL, NULL);
00207 throw std::runtime_error("Error openning dynamic buffer");
00208 }
00209 header_size = avio_close_dyn_buf(format_context_->pb, &header_raw_buffer);
00210
00211
00212 header_buffer.resize(header_size);
00213 memcpy(&header_buffer[0], header_raw_buffer, header_size);
00214
00215 av_free(header_raw_buffer);
00216 }
00217
00218
00219 async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header(
00220 "Server", "web_video_server").header("Cache-Control",
00221 "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header(
00222 "Pragma", "no-cache").header("Expires", "0").header("Max-Age", "0").header("Trailer", "Expires").header(
00223 "Content-type", content_type_).header("Access-Control-Allow-Origin", "*").write(connection_);
00224
00225
00226 connection_->write_and_clear(header_buffer);
00227 }
00228
00229 void LibavStreamer::initializeEncoder()
00230 {
00231 }
00232
00233 void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
00234 {
00235 boost::mutex::scoped_lock lock(encode_mutex_);
00236 if (first_image_timestamp_.isZero())
00237 {
00238 first_image_timestamp_ = time;
00239 }
00240 std::vector<uint8_t> encoded_frame;
00241 #if (LIBAVUTIL_VERSION_MAJOR < 52)
00242 PixelFormat input_coding_format = PIX_FMT_BGR24;
00243 #else
00244 AVPixelFormat input_coding_format = PIX_FMT_BGR24;
00245 #endif
00246 avpicture_fill(tmp_picture_, img.data, input_coding_format, output_width_, output_height_);
00247
00248
00249 if (!sws_context_)
00250 {
00251 static int sws_flags = SWS_BICUBIC;
00252 sws_context_ = sws_getContext(output_width_, output_height_, input_coding_format, output_width_, output_height_,
00253 codec_context_->pix_fmt, sws_flags, NULL, NULL, NULL);
00254 if (!sws_context_)
00255 {
00256 throw std::runtime_error("Could not initialize the conversion context");
00257 }
00258 }
00259
00260 int ret = sws_scale(sws_context_, (const uint8_t * const *)tmp_picture_->data, tmp_picture_->linesize, 0,
00261 output_height_, picture_->data, picture_->linesize);
00262
00263
00264 AVPacket pkt;
00265 int got_packet;
00266 av_init_packet(&pkt);
00267
00268 #if (LIBAVCODEC_VERSION_MAJOR < 54)
00269 int buf_size = 6 * output_width_ * output_height_;
00270 pkt.data = (uint8_t*)av_malloc(buf_size);
00271 pkt.size = avcodec_encode_video(codec_context_, pkt.data, buf_size, frame_);
00272 got_packet = pkt.size > 0;
00273 #else
00274 pkt.data = NULL;
00275 pkt.size = 0;
00276 if (avcodec_encode_video2(codec_context_, &pkt, frame_, &got_packet) < 0)
00277 {
00278 throw std::runtime_error("Error encoding video frame");
00279 }
00280 #endif
00281
00282 if (got_packet)
00283 {
00284 std::size_t size;
00285 uint8_t *output_buf;
00286
00287 double seconds = (time - first_image_timestamp_).toSec();
00288
00289 pkt.pts = (int64_t)(seconds / av_q2d(video_stream_->time_base) * 0.95);
00290 if (pkt.pts <= 0)
00291 pkt.pts = 1;
00292 pkt.dts = AV_NOPTS_VALUE;
00293
00294 if (codec_context_->coded_frame->key_frame)
00295 pkt.flags |= AV_PKT_FLAG_KEY;
00296
00297 pkt.stream_index = video_stream_->index;
00298
00299 if (avio_open_dyn_buf(&format_context_->pb) >= 0)
00300 {
00301 if (av_write_frame(format_context_, &pkt))
00302 {
00303 throw std::runtime_error("Error when writing frame");
00304 }
00305 size = avio_close_dyn_buf(format_context_->pb, &output_buf);
00306
00307 encoded_frame.resize(size);
00308 memcpy(&encoded_frame[0], output_buf, size);
00309
00310 av_free(output_buf);
00311 }
00312 }
00313 else
00314 {
00315 encoded_frame.clear();
00316 }
00317 #if (LIBAVCODEC_VERSION_MAJOR < 54)
00318 av_free(pkt.data);
00319 #endif
00320
00321 av_free_packet(&pkt);
00322
00323 connection_->write_and_clear(encoded_frame);
00324 }
00325
00326 LibavStreamerType::LibavStreamerType(const std::string &format_name, const std::string &codec_name,
00327 const std::string &content_type) :
00328 format_name_(format_name), codec_name_(codec_name), content_type_(content_type)
00329 {
00330 }
00331
00332 boost::shared_ptr<ImageStreamer> LibavStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request,
00333 async_web_server_cpp::HttpConnectionPtr connection,
00334 ros::NodeHandle& nh)
00335 {
00336 return boost::shared_ptr<ImageStreamer>(
00337 new LibavStreamer(request, connection, nh, format_name_, codec_name_, content_type_));
00338 }
00339
00340 std::string LibavStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request)
00341 {
00342 std::stringstream ss;
00343 ss << "<video src=\"/stream?";
00344 ss << request.query;
00345 ss << "\" autoplay=\"true\" preload=\"none\"></video>";
00346 return ss.str();
00347 }
00348
00349 }