00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <stdlib.h>
00037 #include <stdio.h>
00038 #include <string>
00039
00040 #include <set>
00041
00042 #include "ffmpeg_wrapper.h"
00043 #include <boost/bind.hpp>
00044
00045 #ifdef HAVE_AV_CONFIG_H
00046 #undef HAVE_AV_CONFIG_H
00047 #endif
00048
00049 #ifdef __cplusplus
00050 #define __STDC_CONSTANT_MACROS
00051 #ifdef _STDINT_H
00052 #undef _STDINT_H
00053 #endif
00054 # include <stdint.h>
00055 #endif
00056
00057 #define MILLISEC_FOR_FFMPEG_INIT (5*1000)
00058
00059
00060
00061 namespace ros_http_video_streamer
00062 {
00063
00064 extern "C"
00065 {
00066 #include <libavcodec/avcodec.h>
00067 #include <libavformat/avformat.h>
00068 #include "libavutil/intreadwrite.h"
00069 #include "libavformat/avio.h"
00070 #include <libswscale/swscale.h>
00071 #include "libavutil/opt.h"
00072 }
00073
00074
00075 FFMPEG_Wrapper::FFMPEG_Wrapper() :
00076 ffmpeg_codec_(0),
00077 ffmpeg_output_format_(0),
00078 ffmpeg_codec_context_(0),
00079 ffmpeg_format_context_(0),
00080 ffmpeg_src_picture_(new AVPicture),
00081 ffmpeg_dst_picture_(new AVPicture),
00082 ffmpeg_video_st_(0),
00083 ffmpeg_frame_(0),
00084 ffmpeg_video_pts_(0.0),
00085 ffmpeg_sws_ctx_(0),
00086 config_(),
00087 input_width_(-1),
00088 input_height_(-1),
00089 output_width_(-1),
00090 output_height_(-1),
00091 init_(false)
00092 {
00093 }
00094
00095 FFMPEG_Wrapper::~FFMPEG_Wrapper()
00096 {
00097 shutdown();
00098 }
00099
00100 static int ff_lockmgr(void **mutex, enum AVLockOp op)
00101 {
00102 if (NULL == mutex)
00103 return -1;
00104
00105 switch (op)
00106 {
00107 case AV_LOCK_CREATE:
00108 {
00109 *mutex = NULL;
00110 boost::mutex * m = new boost::mutex();
00111 *mutex = static_cast<void*>(m);
00112 break;
00113 }
00114 case AV_LOCK_OBTAIN:
00115 {
00116 boost::mutex * m = static_cast<boost::mutex*>(*mutex);
00117 m->lock();
00118 break;
00119 }
00120 case AV_LOCK_RELEASE:
00121 {
00122 boost::mutex * m = static_cast<boost::mutex*>(*mutex);
00123 m->unlock();
00124 break;
00125 }
00126 case AV_LOCK_DESTROY:
00127 {
00128 boost::mutex * m = static_cast<boost::mutex*>(*mutex);
00129 m->lock();
00130 m->unlock();
00131 delete m;
00132 break;
00133 }
00134 default:
00135 break;
00136 }
00137 return 0;
00138 }
00139
00140
00141
00142 int FFMPEG_Wrapper::init(int input_width,
00143 int input_height,
00144 const ServerConfiguration& config)
00145 {
00146 boost::mutex::scoped_lock lock(frame_mutex_);
00147
00148 time_started_ = boost::posix_time::microsec_clock::local_time();
00149
00150 config_ = config;
00151
00152 input_width_ = input_width;
00153 input_height_ = input_height;
00154
00155 output_width_ = config.frame_width_;
00156 output_height_ = config.frame_height_;
00157
00158 if (output_width_<0)
00159 output_width_ = input_width_;
00160
00161 if (output_height_<0)
00162 output_height_ = input_height_;
00163
00164 av_lockmgr_register(&ff_lockmgr);
00165
00166
00167 avcodec_register_all();
00168 av_register_all();
00169
00170
00171 avformat_alloc_output_context2(&ffmpeg_format_context_, NULL, config_.codec_.c_str(), NULL);
00172 if (!ffmpeg_format_context_) {
00173 return -1;
00174 }
00175
00176 ffmpeg_output_format_ = ffmpeg_format_context_->oformat;
00177
00178
00179
00180 ffmpeg_video_st_ = NULL;
00181 if (ffmpeg_output_format_->video_codec != AV_CODEC_ID_NONE)
00182 {
00183
00184
00185 ffmpeg_codec_ = avcodec_find_encoder(ffmpeg_output_format_->video_codec);
00186 if (!(ffmpeg_codec_))
00187 {
00188 fprintf(stderr, "Codec not found (%s)\n",config_.codec_.c_str());
00189 return -1;
00190 }
00191
00192 ffmpeg_video_st_ = avformat_new_stream(ffmpeg_format_context_, ffmpeg_codec_);
00193 if (!ffmpeg_video_st_)
00194 {
00195 fprintf(stderr, "Could not alloc stream\n");
00196 return -1;
00197 }
00198
00199 ffmpeg_codec_context_ = ffmpeg_video_st_->codec;
00200
00201
00202
00203 avcodec_get_context_defaults3(ffmpeg_codec_context_, ffmpeg_codec_);
00204
00206
00208
00209 ffmpeg_codec_context_->codec_id = ffmpeg_output_format_->video_codec;
00210 ffmpeg_codec_context_->bit_rate = config_.bitrate_;
00211
00212 ffmpeg_codec_context_->width = output_width_;
00213 ffmpeg_codec_context_->height = output_height_;
00214 ffmpeg_codec_context_->delay = 0;
00215
00216 ffmpeg_codec_context_->time_base.den = config_.framerate_+3;
00217 ffmpeg_codec_context_->time_base.num = 1;
00218 ffmpeg_codec_context_->gop_size = config_.gop_;
00219 ffmpeg_codec_context_->pix_fmt = PIX_FMT_YUV420P;
00220 ffmpeg_codec_context_->max_b_frames = 0;
00221
00222 av_opt_set(ffmpeg_codec_context_->priv_data, "quality", config_.profile_.c_str(), 0);
00223
00224 av_opt_set(ffmpeg_codec_context_->priv_data, "deadline", "1", 0);
00225 av_opt_set(ffmpeg_codec_context_->priv_data, "auto-alt-ref", "0", 0);
00226
00227
00228 av_opt_set(ffmpeg_codec_context_->priv_data, "lag-in-frames", "1", 0);
00229 av_opt_set(ffmpeg_codec_context_->priv_data, "rc_lookahead", "1", 0);
00230
00231 av_opt_set(ffmpeg_codec_context_->priv_data, "drop_frame", "1", 0);
00232
00233
00234 av_opt_set(ffmpeg_codec_context_->priv_data, "error-resilient", "1", 0);
00235
00236
00237 int bufsize = 10;
00238 ffmpeg_codec_context_->rc_buffer_size = bufsize;
00239
00240 ffmpeg_codec_context_->rc_initial_buffer_occupancy = bufsize ;
00241
00242 av_opt_set_int(ffmpeg_codec_context_->priv_data, "bufsize", bufsize, 0);
00243 av_opt_set_int(ffmpeg_codec_context_->priv_data, "buf-initial", bufsize, 0);
00244 av_opt_set_int(ffmpeg_codec_context_->priv_data, "buf-optimal", bufsize, 0);
00245
00246
00247 ffmpeg_codec_context_->rc_buffer_aggressivity = 0.5;
00248
00249
00250
00251
00252 if (config_.quality_>0)
00253 ffmpeg_codec_context_->qmin = config_.quality_;
00254
00255
00256
00257
00258 if (ffmpeg_format_context_->oformat->flags & AVFMT_GLOBALHEADER)
00259 ffmpeg_codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER;
00260 }
00261
00262 if (ffmpeg_video_st_)
00263 {
00264 int ret;
00265
00266
00267 {
00268 boost::mutex::scoped_lock lock(codec_mutex_);
00269 if (avcodec_open2(ffmpeg_codec_context_, ffmpeg_codec_, NULL) < 0) {
00270 fprintf(stderr, "Could not open video codec\n");
00271 return -1;
00272 }
00273 }
00274
00275
00276 ffmpeg_frame_ = avcodec_alloc_frame();
00277 if (!ffmpeg_frame_) {
00278 fprintf(stderr, "Could not allocate video ffmpeg_frame_\n");
00279 return -1;
00280 }
00281
00282
00283 ret = avpicture_alloc(ffmpeg_dst_picture_, ffmpeg_codec_context_->pix_fmt, output_width_, output_height_);
00284 if (ret < 0) {
00285 fprintf(stderr, "Could not allocate picture\n");
00286 return -1;
00287 }
00288
00289
00290
00291
00292 ret = avpicture_alloc(ffmpeg_src_picture_, AV_PIX_FMT_RGB24, input_width_, input_height_);
00293 if (ret < 0) {
00294 fprintf(stderr, "Could not allocate temporary picture\n");
00295 return -1;
00296 }
00297
00298
00299 *((AVPicture *)ffmpeg_frame_) = *ffmpeg_dst_picture_;
00300
00301 av_dump_format(ffmpeg_format_context_, 0, "", 1);
00302
00303 ffmpeg_output_format_->flags |= AVFMT_NOFILE;
00304
00305 if (ffmpeg_frame_)
00306 ffmpeg_frame_->pts = 0;
00307 }
00308
00309 init_ = true;
00310
00311 return 0;
00312 }
00313
00314
00315 void FFMPEG_Wrapper::shutdown()
00316 {
00317 boost::mutex::scoped_lock lock(frame_mutex_);
00318
00319 if (init_)
00320 {
00321
00322
00323 boost::posix_time::ptime now = boost::posix_time::microsec_clock::local_time();
00324 boost::posix_time::time_duration diff = now - time_started_;
00325 unsigned int milisec_used = std::max(100u,(unsigned int)diff.total_milliseconds());
00326
00327 if (milisec_used < MILLISEC_FOR_FFMPEG_INIT)
00328 {
00329
00330 boost::this_thread::sleep(boost::posix_time::milliseconds(MILLISEC_FOR_FFMPEG_INIT - milisec_used));
00331 }
00332
00333
00334
00335 if (ffmpeg_codec_context_)
00336 {
00337 boost::mutex::scoped_lock lock(codec_mutex_);
00338 avcodec_close(ffmpeg_codec_context_);
00339 }
00340
00341
00342 if (ffmpeg_frame_)
00343 avcodec_free_frame(&ffmpeg_frame_);
00344
00345 if (ffmpeg_format_context_)
00346 {
00347
00348
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358 avformat_free_context(ffmpeg_format_context_);
00359 }
00360
00361
00362 if (ffmpeg_src_picture_)
00363 av_free(ffmpeg_src_picture_);
00364
00365 if (ffmpeg_dst_picture_)
00366 av_free(ffmpeg_dst_picture_);
00367
00368 if (ffmpeg_sws_ctx_)
00369 sws_freeContext(ffmpeg_sws_ctx_);
00370
00371 init_ = false;
00372
00373 }
00374 }
00375
00376 void FFMPEG_Wrapper::encode_bgr_frame(uint8_t *bgr_data, std::vector<uint8_t>& encoded_frame)
00377 {
00378 encode_frame<PIX_FMT_BGR24>(bgr_data, encoded_frame);
00379 }
00380
00381 void FFMPEG_Wrapper::encode_rgb_frame(uint8_t *rgb_data, std::vector<uint8_t>& encoded_frame)
00382 {
00383 encode_frame<PIX_FMT_RGB24>(rgb_data, encoded_frame);
00384 }
00385
00386 void FFMPEG_Wrapper::encode_mono8_frame(uint8_t *gray8_data, std::vector<uint8_t>& encoded_frame)
00387 {
00388 encode_frame<PIX_FMT_GRAY8>(gray8_data, encoded_frame);
00389 }
00390
00391 void FFMPEG_Wrapper::encode_mono16_frame(uint8_t *gray16_data, std::vector<uint8_t>& encoded_frame)
00392 {
00393 encode_frame<PIX_FMT_GRAY16LE>(gray16_data, encoded_frame);
00394 }
00395
00396 template <int CODING_FORMAT>
00397 void FFMPEG_Wrapper::encode_frame(uint8_t *image_data, std::vector<uint8_t>& encoded_frame)
00398 {
00399
00400 boost::mutex::scoped_lock lock(frame_mutex_);
00401
00402 avpicture_fill(ffmpeg_src_picture_, image_data, (AVPixelFormat)CODING_FORMAT, input_width_, input_height_);
00403
00404
00405 if (!ffmpeg_sws_ctx_) {
00406 static int sws_flags = SWS_BICUBIC;
00407 ffmpeg_sws_ctx_ = sws_getContext(input_width_, input_height_, (AVPixelFormat)CODING_FORMAT,
00408 output_width_, output_height_, ffmpeg_codec_context_->pix_fmt,
00409 sws_flags, NULL, NULL, NULL);
00410 if (!ffmpeg_sws_ctx_) {
00411 fprintf(stderr,
00412 "Could not initialize the conversion context\n");
00413 return;
00414 }
00415 }
00416
00417 sws_scale(ffmpeg_sws_ctx_,
00418 (const uint8_t * const *)ffmpeg_src_picture_->data,
00419 ffmpeg_src_picture_->linesize, 0, input_height_, ffmpeg_dst_picture_->data, ffmpeg_dst_picture_->linesize);
00420
00421
00422 AVPacket pkt;
00423 int got_output;
00424
00425 av_init_packet(&pkt);
00426 pkt.data = NULL;
00427 pkt.size = 0;
00428
00429 if (avcodec_encode_video2(ffmpeg_codec_context_, &pkt, ffmpeg_frame_, &got_output) < 0)
00430 {
00431 fprintf(stderr, "Error encoding video ffmpeg_frame_\n");
00432 return;
00433 }
00434
00435
00436 if (got_output)
00437 {
00438 std::size_t size;
00439 uint8_t* output_buf;
00440
00441 if (ffmpeg_codec_context_->coded_frame->pts != AV_NOPTS_VALUE)
00442 pkt.pts = av_rescale_q(ffmpeg_codec_context_->coded_frame->pts, ffmpeg_codec_context_->time_base, ffmpeg_video_st_->time_base);
00443
00444 pkt.pts= ffmpeg_codec_context_->coded_frame->pts;
00445
00446 if (ffmpeg_codec_context_->coded_frame->key_frame)
00447 pkt.flags |= AV_PKT_FLAG_KEY;
00448
00449 pkt.stream_index = ffmpeg_video_st_->index;
00450
00451 if (avio_open_dyn_buf(&ffmpeg_format_context_->pb) >= 0)
00452 {
00453 ffmpeg_format_context_->pb->seekable = 0;
00454
00455 if (av_write_frame(ffmpeg_format_context_, &pkt))
00456 {
00457 fprintf(stderr, "Error occurred when opening output file\n");
00458 return;
00459 }
00460
00461 size = avio_close_dyn_buf(ffmpeg_format_context_->pb, &output_buf);
00462
00463 encoded_frame.resize(size);
00464 memcpy(&encoded_frame[0], output_buf, size);
00465
00466 av_free(output_buf);
00467 }
00468 }
00469 else
00470 {
00471 encoded_frame.clear();
00472 }
00473
00474 av_free_packet(&pkt);
00475
00476 AVRational timebase = ffmpeg_codec_context_->time_base;
00477
00478 timebase.den += 2;
00479
00480
00481 ffmpeg_frame_->pts += av_rescale_q(1, timebase, ffmpeg_video_st_->time_base);
00482 }
00483
00484 void FFMPEG_Wrapper::get_header(std::vector<uint8_t>& header)
00485 {
00486 boost::mutex::scoped_lock lock(frame_mutex_);
00487
00488 std::size_t size;
00489 uint8_t* output_buf;
00490
00491
00492 av_dict_set(&ffmpeg_format_context_->metadata, "author" , "ROS topic http streamer" , 0);
00493 av_dict_set(&ffmpeg_format_context_->metadata, "comment" , "this is awesome" , 0);
00494 av_dict_set(&ffmpeg_format_context_->metadata, "copyright", "BSD", 0);
00495 av_dict_set(&ffmpeg_format_context_->metadata, "title" , "ROS Topic Stream" , 0);
00496
00497 if (avio_open_dyn_buf(&ffmpeg_format_context_->pb) >= 0)
00498 {
00499 ffmpeg_format_context_->pb->seekable = 0;
00500
00501 if (avformat_write_header(ffmpeg_format_context_, NULL) < 0)
00502 {
00503 fprintf(stderr, "Error occurred when opening output file\n");
00504 return;
00505 }
00506
00507
00508
00509 size = avio_close_dyn_buf(ffmpeg_format_context_->pb, &output_buf);
00510
00511
00512 header.resize(size);
00513 memcpy(&header[0], output_buf, size);
00514
00515 av_free(output_buf);
00516 }
00517 }
00518
00519 void FFMPEG_Wrapper::get_trailer(std::vector<uint8_t>& trailer)
00520 {
00521 std::size_t size;
00522 uint8_t* output_buf;
00523
00524 boost::mutex::scoped_lock lock(frame_mutex_);
00525
00526 if (avio_open_dyn_buf(&ffmpeg_format_context_->pb) >= 0)
00527 {
00528 ffmpeg_format_context_->pb->seekable = 0;
00529
00530 if (av_write_trailer(ffmpeg_format_context_) < 0)
00531 {
00532 fprintf(stderr, "Error occurred when opening output file\n");
00533 return;
00534 }
00535
00536 size = avio_close_dyn_buf(ffmpeg_format_context_->pb, &output_buf);
00537
00538
00539 trailer.resize(size);
00540 memcpy(&trailer[0], output_buf, size);
00541
00542 av_free(output_buf);
00543 }
00544 }
00545
00546 }