88namespace web_video_server
99{
1010
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-
5111LibavStreamer::LibavStreamer (const async_web_server_cpp::HttpRequest &request,
5212 async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh,
5313 const std::string &format_name, const std::string &codec_name,
5414 const std::string &content_type) :
55- ImageTransportImageStreamer (request, connection, nh), output_format_( 0 ), format_context_(0 ), codec_(0 ), codec_context_(0 ), video_stream_(
15+ ImageTransportImageStreamer (request, connection, nh), format_context_(0 ), codec_(0 ), codec_context_(0 ), video_stream_(
5616 0 ), frame_(0 ), sws_context_(0 ), first_image_timestamp_(0 ), format_name_(
5717 format_name), codec_name_(codec_name), content_type_(content_type), opt_(0 ), io_buffer_(0 )
5818{
@@ -61,9 +21,6 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request,
6121 qmin_ = request.get_query_param_value_or_default <int >(" qmin" , 10 );
6222 qmax_ = request.get_query_param_value_or_default <int >(" qmax" , 42 );
6323 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 ();
6724}
6825
6926LibavStreamer::~LibavStreamer ()
@@ -111,15 +68,18 @@ void LibavStreamer::initialize(const cv::Mat &img)
11168 NULL , NULL );
11269 throw std::runtime_error (" Error allocating ffmpeg format context" );
11370 }
114- output_format_ = av_guess_format (format_name_.c_str (), NULL , NULL );
115- if (!output_format_ )
71+ const AVOutputFormat* guessed_format = av_guess_format (format_name_.c_str (), NULL , NULL );
72+ if (!guessed_format )
11673 {
11774 async_web_server_cpp::HttpReply::stock_reply (async_web_server_cpp::HttpReply::internal_server_error)(request_,
11875 connection_,
11976 NULL , NULL );
12077 throw std::runtime_error (" Error looking up output format" );
12178 }
122- format_context_->oformat = output_format_;
79+
80+
81+ output_format_ = *guessed_format;
82+ format_context_->oformat = &output_format_;
12383
12484 // Set up custom IO callback.
12585 size_t io_buffer_size = 3 * 1024 ; // 3M seen elsewhere and adjudged good
@@ -134,12 +94,12 @@ void LibavStreamer::initialize(const cv::Mat &img)
13494 }
13595 io_ctx->seekable = 0 ; // no seeking, it's a stream
13696 format_context_->pb = io_ctx;
137- output_format_-> flags |= AVFMT_FLAG_CUSTOM_IO;
138- output_format_-> flags |= AVFMT_NOFILE;
97+ output_format_. flags |= AVFMT_FLAG_CUSTOM_IO;
98+ output_format_. flags |= AVFMT_NOFILE;
13999
140100 // Load codec
141101 if (codec_name_.empty ()) // use default codec if none specified
142- codec_ = avcodec_find_encoder (output_format_-> video_codec );
102+ codec_ = avcodec_find_encoder (output_format_. video_codec );
143103 else
144104 codec_ = avcodec_find_encoder_by_name (codec_name_.c_str ());
145105 if (!codec_)
@@ -157,11 +117,10 @@ void LibavStreamer::initialize(const cv::Mat &img)
157117 NULL , NULL );
158118 throw std::runtime_error (" Error creating video stream" );
159119 }
160- codec_context_ = video_stream_->codec ;
161120
162- // Set options
163- avcodec_get_context_defaults3 (codec_context_, codec_);
121+ codec_context_ = avcodec_alloc_context3 (codec_);
164122
123+ // Set options
165124 codec_context_->codec_id = codec_->id ;
166125 codec_context_->bit_rate = bitrate_;
167126
@@ -209,7 +168,7 @@ void LibavStreamer::initialize(const cv::Mat &img)
209168 frame_->width = output_width_;
210169 frame_->height = output_height_;
211170 frame_->format = codec_context_->pix_fmt ;
212- output_format_-> flags |= AVFMT_NOFILE;
171+ output_format_. flags |= AVFMT_NOFILE;
213172
214173 // Generate header
215174 std::vector<uint8_t > header_buffer;
@@ -289,9 +248,8 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
289248#endif
290249
291250 // Encode the frame
292- AVPacket pkt;
251+ AVPacket* pkt = av_packet_alloc () ;
293252 int got_packet;
294- av_init_packet (&pkt);
295253
296254#if (LIBAVCODEC_VERSION_MAJOR < 54)
297255 int buf_size = 6 * output_width_ * output_height_;
@@ -306,16 +264,15 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
306264 throw std::runtime_error (" Error encoding video frame" );
307265 }
308266#else
309- pkt.data = NULL ; // packet data will be allocated by the encoder
310- pkt.size = 0 ;
311267 if (avcodec_send_frame (codec_context_, frame_) < 0 )
312268 {
313269 throw std::runtime_error (" Error encoding video frame" );
314270 }
315- if (avcodec_receive_packet (codec_context_, & pkt) < 0 )
271+ if (avcodec_receive_packet (codec_context_, pkt) < 0 )
316272 {
317273 throw std::runtime_error (" Error retrieving encoded packet" );
318274 }
275+ got_packet = pkt->size > 0 ;
319276#endif
320277
321278 if (got_packet)
@@ -325,17 +282,17 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
325282
326283 double seconds = (time - first_image_timestamp_).seconds ();
327284 // 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;
285+ pkt-> pts = (int64_t )(seconds / av_q2d (video_stream_->time_base ) * 0.95 );
286+ if (pkt-> pts <= 0 )
287+ pkt-> pts = 1 ;
288+ pkt-> dts = AV_NOPTS_VALUE;
332289
333- if (pkt. flags &AV_PKT_FLAG_KEY)
334- pkt. flags |= AV_PKT_FLAG_KEY;
290+ if (pkt-> flags &AV_PKT_FLAG_KEY)
291+ pkt-> flags |= AV_PKT_FLAG_KEY;
335292
336- pkt. stream_index = video_stream_->index ;
293+ pkt-> stream_index = video_stream_->index ;
337294
338- if (av_write_frame (format_context_, & pkt))
295+ if (av_write_frame (format_context_, pkt))
339296 {
340297 throw std::runtime_error (" Error when writing frame" );
341298 }
@@ -351,7 +308,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
351308#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1)
352309 av_free_packet (&pkt);
353310#else
354- av_packet_unref (& pkt);
311+ av_packet_unref (pkt);
355312#endif
356313
357314 connection_->write_and_clear (encoded_frame);
0 commit comments