libav_streamer.cpp
Go to the documentation of this file.
2 #include "async_web_server_cpp/http_reply.hpp"
3 
4 /*https://stackoverflow.com/questions/46884682/error-in-building-opencv-with-ffmpeg*/
5 #define AV_CODEC_FLAG_GLOBAL_HEADER (1 << 22)
6 #define CODEC_FLAG_GLOBAL_HEADER AV_CODEC_FLAG_GLOBAL_HEADER
7 
8 namespace web_video_server
9 {
10 
11 static int ffmpeg_boost_mutex_lock_manager(void **mutex, enum AVLockOp op)
12 {
13  if (NULL == mutex)
14  return -1;
15 
16  switch (op)
17  {
18  case AV_LOCK_CREATE:
19  {
20  *mutex = NULL;
21  boost::mutex *m = new boost::mutex();
22  *mutex = static_cast<void *>(m);
23  break;
24  }
25  case AV_LOCK_OBTAIN:
26  {
27  boost::mutex *m = static_cast<boost::mutex *>(*mutex);
28  m->lock();
29  break;
30  }
31  case AV_LOCK_RELEASE:
32  {
33  boost::mutex *m = static_cast<boost::mutex *>(*mutex);
34  m->unlock();
35  break;
36  }
37  case AV_LOCK_DESTROY:
38  {
39  boost::mutex *m = static_cast<boost::mutex *>(*mutex);
40  m->lock();
41  m->unlock();
42  delete m;
43  break;
44  }
45  default:
46  break;
47  }
48  return 0;
49 }
50 
51 LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request,
52  async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle& nh,
53  const std::string &format_name, const std::string &codec_name,
54  const std::string &content_type) :
55  ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_(
56  0), frame_(0), sws_context_(0), first_image_timestamp_(0), format_name_(
57  format_name), codec_name_(codec_name), content_type_(content_type), opt_(0), io_buffer_(0)
58 {
59 
60  bitrate_ = request.get_query_param_value_or_default<int>("bitrate", 100000);
61  qmin_ = request.get_query_param_value_or_default<int>("qmin", 10);
62  qmax_ = request.get_query_param_value_or_default<int>("qmax", 42);
63  gop_ = request.get_query_param_value_or_default<int>("gop", 250);
64 
65  av_lockmgr_register(&ffmpeg_boost_mutex_lock_manager);
66  av_register_all();
67 }
68 
70 {
71  if (codec_context_)
72  avcodec_close(codec_context_);
73  if (frame_)
74  {
75 #if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1)
76  av_free(frame_);
77  frame_ = NULL;
78 #else
79  av_frame_free(&frame_);
80 #endif
81  }
82  if (io_buffer_)
83  delete io_buffer_;
84  if (format_context_) {
85  if (format_context_->pb)
86  av_free(format_context_->pb);
87  avformat_free_context(format_context_);
88  }
89  if (sws_context_)
90  sws_freeContext(sws_context_);
91 }
92 
93 // output callback for ffmpeg IO context
94 static int dispatch_output_packet(void* opaque, uint8_t* buffer, int buffer_size)
95 {
96  async_web_server_cpp::HttpConnectionPtr connection = *((async_web_server_cpp::HttpConnectionPtr*) opaque);
97  std::vector<uint8_t> encoded_frame;
98  encoded_frame.assign(buffer, buffer + buffer_size);
99  connection->write_and_clear(encoded_frame);
100  return 0; // TODO: can this fail?
101 }
102 
103 void LibavStreamer::initialize(const cv::Mat &img)
104 {
105  // Load format
106  format_context_ = avformat_alloc_context();
107  if (!format_context_)
108  {
109  async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
110  connection_,
111  NULL, NULL);
112  throw std::runtime_error("Error allocating ffmpeg format context");
113  }
114  output_format_ = av_guess_format(format_name_.c_str(), NULL, NULL);
115  if (!output_format_)
116  {
117  async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
118  connection_,
119  NULL, NULL);
120  throw std::runtime_error("Error looking up output format");
121  }
122  format_context_->oformat = output_format_;
123 
124  // Set up custom IO callback.
125  size_t io_buffer_size = 3 * 1024; // 3M seen elsewhere and adjudged good
126  io_buffer_ = new unsigned char[io_buffer_size];
127  AVIOContext* io_ctx = avio_alloc_context(io_buffer_, io_buffer_size, AVIO_FLAG_WRITE, &connection_, NULL, dispatch_output_packet, NULL);
128  if (!io_ctx)
129  {
130  async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
131  connection_,
132  NULL, NULL);
133  throw std::runtime_error("Error setting up IO context");
134  }
135  io_ctx->seekable = 0; // no seeking, it's a stream
136  format_context_->pb = io_ctx;
137  output_format_->flags |= AVFMT_FLAG_CUSTOM_IO;
138  output_format_->flags |= AVFMT_NOFILE;
139 
140  // Load codec
141  if (codec_name_.empty()) // use default codec if none specified
142  codec_ = avcodec_find_encoder(output_format_->video_codec);
143  else
144  codec_ = avcodec_find_encoder_by_name(codec_name_.c_str());
145  if (!codec_)
146  {
147  async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
148  connection_,
149  NULL, NULL);
150  throw std::runtime_error("Error looking up codec");
151  }
152  video_stream_ = avformat_new_stream(format_context_, codec_);
153  if (!video_stream_)
154  {
155  async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
156  connection_,
157  NULL, NULL);
158  throw std::runtime_error("Error creating video stream");
159  }
160  codec_context_ = video_stream_->codec;
161 
162  // Set options
163  avcodec_get_context_defaults3(codec_context_, codec_);
164 
165  codec_context_->codec_id = codec_->id;
166  codec_context_->bit_rate = bitrate_;
167 
168  codec_context_->width = output_width_;
169  codec_context_->height = output_height_;
170  codec_context_->delay = 0;
171 
172  video_stream_->time_base.num = 1;
173  video_stream_->time_base.den = 1000;
174 
175  codec_context_->time_base.num = 1;
176  codec_context_->time_base.den = 1;
177  codec_context_->gop_size = gop_;
178  codec_context_->pix_fmt = AV_PIX_FMT_YUV420P;
179  codec_context_->max_b_frames = 0;
180 
181  // Quality settings
182  codec_context_->qmin = qmin_;
183  codec_context_->qmax = qmax_;
184 
186 
187  // Some formats want stream headers to be separate
188  if (format_context_->oformat->flags & AVFMT_GLOBALHEADER)
190 
191  // Open Codec
192  if (avcodec_open2(codec_context_, codec_, NULL) < 0)
193  {
194  async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
195  connection_,
196  NULL, NULL);
197  throw std::runtime_error("Could not open video codec");
198  }
199 
200  // Allocate frame buffers
201 #if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1)
202  frame_ = avcodec_alloc_frame();
203 #else
204  frame_ = av_frame_alloc();
205 #endif
206  av_image_alloc(frame_->data, frame_->linesize, output_width_, output_height_,
207  codec_context_->pix_fmt, 1);
208 
209  frame_->width = output_width_;
210  frame_->height = output_height_;
211  frame_->format = codec_context_->pix_fmt;
212  output_format_->flags |= AVFMT_NOFILE;
213 
214  // Generate header
215  std::vector<uint8_t> header_buffer;
216  std::size_t header_size;
217  uint8_t *header_raw_buffer;
218  // define meta data
219  av_dict_set(&format_context_->metadata, "author", "ROS web_video_server", 0);
220  av_dict_set(&format_context_->metadata, "title", topic_.c_str(), 0);
221 
222  // Send response headers
223  async_web_server_cpp::HttpReply::builder(async_web_server_cpp::HttpReply::ok).header("Connection", "close").header(
224  "Server", "web_video_server").header("Cache-Control",
225  "no-cache, no-store, must-revalidate, pre-check=0, post-check=0, max-age=0").header(
226  "Pragma", "no-cache").header("Expires", "0").header("Max-Age", "0").header("Trailer", "Expires").header(
227  "Content-type", content_type_).header("Access-Control-Allow-Origin", "*").write(connection_);
228 
229  // Send video stream header
230  if (avformat_write_header(format_context_, &opt_) < 0)
231  {
232  async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
233  connection_,
234  NULL, NULL);
235  throw std::runtime_error("Error openning dynamic buffer");
236  }
237 }
238 
240 {
241 }
242 
243 void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
244 {
245  boost::mutex::scoped_lock lock(encode_mutex_);
247  {
248  first_image_timestamp_ = time;
249  }
250  std::vector<uint8_t> encoded_frame;
251 #if (LIBAVUTIL_VERSION_MAJOR < 53)
252  PixelFormat input_coding_format = PIX_FMT_BGR24;
253 #else
254  AVPixelFormat input_coding_format = AV_PIX_FMT_BGR24;
255 #endif
256 
257 #if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1)
258  AVPicture *raw_frame = new AVPicture;
259  avpicture_fill(raw_frame, img.data, input_coding_format, output_width_, output_height_);
260 #else
261  AVFrame *raw_frame = av_frame_alloc();
262  av_image_fill_arrays(raw_frame->data, raw_frame->linesize,
263  img.data, input_coding_format, output_width_, output_height_, 1);
264 #endif
265 
266 
267 
268  // Convert from opencv to libav
269  if (!sws_context_)
270  {
271  static int sws_flags = SWS_BICUBIC;
272  sws_context_ = sws_getContext(output_width_, output_height_, input_coding_format, output_width_, output_height_,
273  codec_context_->pix_fmt, sws_flags, NULL, NULL, NULL);
274  if (!sws_context_)
275  {
276  throw std::runtime_error("Could not initialize the conversion context");
277  }
278  }
279 
280 
281  int ret = sws_scale(sws_context_,
282  (const uint8_t * const *)raw_frame->data, raw_frame->linesize, 0,
283  output_height_, frame_->data, frame_->linesize);
284 
285 #if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1)
286  delete raw_frame;
287 #else
288  av_frame_free(&raw_frame);
289 #endif
290 
291  // Encode the frame
292  AVPacket pkt;
293  int got_packet;
294  av_init_packet(&pkt);
295 
296 #if (LIBAVCODEC_VERSION_MAJOR < 54)
297  int buf_size = 6 * output_width_ * output_height_;
298  pkt.data = (uint8_t*)av_malloc(buf_size);
299  pkt.size = avcodec_encode_video(codec_context_, pkt.data, buf_size, frame_);
300  got_packet = pkt.size > 0;
301 #elif (LIBAVCODEC_VERSION_MAJOR < 57)
302  pkt.data = NULL; // packet data will be allocated by the encoder
303  pkt.size = 0;
304  if (avcodec_encode_video2(codec_context_, &pkt, frame_, &got_packet) < 0)
305  {
306  throw std::runtime_error("Error encoding video frame");
307  }
308 #else
309  pkt.data = NULL; // packet data will be allocated by the encoder
310  pkt.size = 0;
311  if (avcodec_send_frame(codec_context_, frame_) < 0)
312  {
313  throw std::runtime_error("Error encoding video frame");
314  }
315  if (avcodec_receive_packet(codec_context_, &pkt) < 0)
316  {
317  throw std::runtime_error("Error retrieving encoded packet");
318  }
319 #endif
320 
321  if (got_packet)
322  {
323  std::size_t size;
324  uint8_t *output_buf;
325 
326  double seconds = (time - first_image_timestamp_).toSec();
327  // Encode video at 1/0.95 to minimize delay
328  pkt.pts = (int64_t)(seconds / av_q2d(video_stream_->time_base) * 0.95);
329  if (pkt.pts <= 0)
330  pkt.pts = 1;
331  pkt.dts = AV_NOPTS_VALUE;
332 
333  if (pkt.flags&AV_PKT_FLAG_KEY)
334  pkt.flags |= AV_PKT_FLAG_KEY;
335 
336  pkt.stream_index = video_stream_->index;
337 
338  if (av_write_frame(format_context_, &pkt))
339  {
340  throw std::runtime_error("Error when writing frame");
341  }
342  }
343  else
344  {
345  encoded_frame.clear();
346  }
347 #if LIBAVCODEC_VERSION_INT < 54
348  av_free(pkt.data);
349 #endif
350 
351 #if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1)
352  av_free_packet(&pkt);
353 #else
354  av_packet_unref(&pkt);
355 #endif
356 
357  connection_->write_and_clear(encoded_frame);
358 }
359 
360 LibavStreamerType::LibavStreamerType(const std::string &format_name, const std::string &codec_name,
361  const std::string &content_type) :
362  format_name_(format_name), codec_name_(codec_name), content_type_(content_type)
363 {
364 }
365 
366 boost::shared_ptr<ImageStreamer> LibavStreamerType::create_streamer(const async_web_server_cpp::HttpRequest &request,
367  async_web_server_cpp::HttpConnectionPtr connection,
368  ros::NodeHandle& nh)
369 {
371  new LibavStreamer(request, connection, nh, format_name_, codec_name_, content_type_));
372 }
373 
374 std::string LibavStreamerType::create_viewer(const async_web_server_cpp::HttpRequest &request)
375 {
376  std::stringstream ss;
377  ss << "<video src=\"/stream?";
378  ss << request.query;
379  ss << "\" autoplay=\"true\" preload=\"none\"></video>";
380  return ss.str();
381 }
382 
383 }
static int dispatch_output_packet(void *opaque, uint8_t *buffer, int buffer_size)
AVFormatContext * format_context_
async_web_server_cpp::HttpConnectionPtr connection_
virtual void sendImage(const cv::Mat &, const ros::Time &time)
LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh, const std::string &format_name, const std::string &codec_name, const std::string &content_type)
std::string create_viewer(const async_web_server_cpp::HttpRequest &request)
boost::shared_ptr< ImageStreamer > create_streamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, ros::NodeHandle &nh)
virtual void initialize(const cv::Mat &)
async_web_server_cpp::HttpRequest request_
#define CODEC_FLAG_GLOBAL_HEADER
struct SwsContext * sws_context_
LibavStreamerType(const std::string &format_name, const std::string &codec_name, const std::string &content_type)
static int ffmpeg_boost_mutex_lock_manager(void **mutex, enum AVLockOp op)


web_video_server
Author(s): Mitchell Wills
autogenerated on Wed Jun 5 2019 20:38:04