@@ -60,16 +60,24 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request,
6060 bitrate_ = request.get_query_param_value_or_default <int >(" bitrate" , 100000 );
6161 qmin_ = request.get_query_param_value_or_default <int >(" qmin" , 10 );
6262 qmax_ = request.get_query_param_value_or_default <int >(" qmax" , 42 );
63- gop_ = request.get_query_param_value_or_default <int >(" gop" , 250 );
63+ gop_ = request.get_query_param_value_or_default <int >(" gop" , 25 );
6464
65+ #if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) )
6566 av_lockmgr_register (&ffmpeg_boost_mutex_lock_manager);
6667 av_register_all ();
68+ #endif
6769}
6870
6971LibavStreamer::~LibavStreamer ()
7072{
7173 if (codec_context_)
74+ {
75+ #if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) )
7276 avcodec_close (codec_context_);
77+ #else
78+ avcodec_free_context (&codec_context_);
79+ #endif
80+ }
7381 if (frame_)
7482 {
7583#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1)
@@ -134,6 +142,7 @@ void LibavStreamer::initialize(const cv::Mat &img)
134142 }
135143 io_ctx->seekable = 0 ; // no seeking, it's a stream
136144 format_context_->pb = io_ctx;
145+ format_context_->max_interleave_delta = 0 ;
137146 output_format_->flags |= AVFMT_FLAG_CUSTOM_IO;
138147 output_format_->flags |= AVFMT_NOFILE;
139148
@@ -157,7 +166,11 @@ void LibavStreamer::initialize(const cv::Mat &img)
157166 NULL , NULL );
158167 throw std::runtime_error (" Error creating video stream" );
159168 }
169+ #if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) )
160170 codec_context_ = video_stream_->codec ;
171+ #else
172+ codec_context_ = avcodec_alloc_context3 (codec_);
173+ #endif
161174
162175 // Set options
163176 avcodec_get_context_defaults3 (codec_context_, codec_);
@@ -182,11 +195,14 @@ void LibavStreamer::initialize(const cv::Mat &img)
182195 codec_context_->qmin = qmin_;
183196 codec_context_->qmax = qmax_;
184197
198+ #if ( LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(58,9,100) )
199+ avcodec_parameters_from_context (video_stream_->codecpar , codec_context_);
200+ #endif
201+
185202 initializeEncoder ();
186203
187- // Some formats want stream headers to be separate
188- if (format_context_->oformat ->flags & AVFMT_GLOBALHEADER)
189- codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER;
204+ codec_context_->flags |= AV_CODEC_FLAG_LOW_DELAY;
205+ codec_context_->max_b_frames = 0 ;
190206
191207 // Open Codec
192208 if (avcodec_open2 (codec_context_, codec_, NULL ) < 0 )
@@ -306,15 +322,29 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
306322 throw std::runtime_error (" Error encoding video frame" );
307323 }
308324#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 )
325+ ret = avcodec_send_frame (codec_context_, frame_);
326+ if (ret == AVERROR_EOF)
327+ {
328+ ROS_DEBUG_STREAM (" avcodec_send_frame() encoder flushed" );
329+ }
330+ else if (ret == AVERROR (EAGAIN))
331+ {
332+ ROS_DEBUG_STREAM (" avcodec_send_frame() need output read out" );
333+ }
334+ if (ret < 0 )
312335 {
313336 throw std::runtime_error (" Error encoding video frame" );
314337 }
315- if (avcodec_receive_packet (codec_context_, &pkt) < 0 )
338+ ret = avcodec_receive_packet (codec_context_, &pkt);
339+ got_packet = pkt.size > 0 ;
340+ if (ret == AVERROR_EOF)
341+ {
342+ ROS_DEBUG_STREAM (" avcodec_recieve_packet() encoder flushed" );
343+ }
344+ else if (ret == AVERROR (EAGAIN))
316345 {
317- throw std::runtime_error (" Error retrieving encoded packet" );
346+ ROS_DEBUG_STREAM (" avcodec_recieve_packet() need more input" );
347+ got_packet = 0 ;
318348 }
319349#endif
320350
0 commit comments