From 1f6a5b75262c5b7ddbcc99bc0c0eadded96bf346 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Wed, 2 Oct 2024 12:08:21 +0200 Subject: [PATCH] Fix usage of deprecated libavcodec functions (#150) * Fix usage of deprecated libavcodec functions * Drop compatibility with old ffmpeg libraries * backport #103 * Remove remaining avcodec version check * Use rclcpp debug logs instead of cerr * Remove redundant vector * Fix segfault on write_header * Allow overriding width and height * Fix warning about missing timestamps --- include/web_video_server/libav_streamer.h | 3 +- src/image_streamer.cpp | 3 +- src/libav_streamer.cpp | 177 ++++++---------------- 3 files changed, 48 insertions(+), 135 deletions(-) diff --git a/include/web_video_server/libav_streamer.h b/include/web_video_server/libav_streamer.h index 643e3b3..635be1c 100644 --- a/include/web_video_server/libav_streamer.h +++ b/include/web_video_server/libav_streamer.h @@ -34,9 +34,8 @@ class LibavStreamer : public ImageTransportImageStreamer virtual void initializeEncoder(); virtual void sendImage(const cv::Mat&, const rclcpp::Time& time); virtual void initialize(const cv::Mat&); - AVOutputFormat* output_format_; AVFormatContext* format_context_; - AVCodec* codec_; + const AVCodec* codec_; AVCodecContext* codec_context_; AVStream* video_stream_; diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index 9309be8..a91c31a 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -171,8 +171,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C } last_frame = nh_->now(); - sendImage(output_size_image, last_frame ); - + sendImage(output_size_image, msg->header.stamp); } catch (cv_bridge::Exception &e) { diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 28d0425..0e490ac 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -8,51 +8,11 @@ namespace web_video_server { -static int ffmpeg_boost_mutex_lock_manager(void **mutex, enum AVLockOp op) -{ - if (NULL == mutex) - return -1; - - switch (op) - { - case AV_LOCK_CREATE: - { - *mutex = NULL; - boost::mutex *m = new boost::mutex(); - *mutex = static_cast(m); - break; - } - case AV_LOCK_OBTAIN: - { - boost::mutex *m = static_cast(*mutex); - m->lock(); - break; - } - case AV_LOCK_RELEASE: - { - boost::mutex *m = static_cast(*mutex); - m->unlock(); - break; - } - case AV_LOCK_DESTROY: - { - boost::mutex *m = static_cast(*mutex); - m->lock(); - m->unlock(); - delete m; - break; - } - default: - break; - } - return 0; -} - LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, async_web_server_cpp::HttpConnectionPtr connection, rclcpp::Node::SharedPtr nh, const std::string &format_name, const std::string &codec_name, const std::string &content_type) : - ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_( + ImageTransportImageStreamer(request, connection, nh), format_context_(0), codec_(0), codec_context_(0), video_stream_( 0), frame_(0), sws_context_(0), first_image_timestamp_(0), format_name_( format_name), codec_name_(codec_name), content_type_(content_type), opt_(0), io_buffer_(0) { @@ -60,24 +20,18 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, bitrate_ = request.get_query_param_value_or_default("bitrate", 100000); qmin_ = request.get_query_param_value_or_default("qmin", 10); qmax_ = request.get_query_param_value_or_default("qmax", 42); - gop_ = request.get_query_param_value_or_default("gop", 250); - - av_lockmgr_register(&ffmpeg_boost_mutex_lock_manager); - av_register_all(); + gop_ = request.get_query_param_value_or_default("gop", 25); } LibavStreamer::~LibavStreamer() { if (codec_context_) - avcodec_close(codec_context_); + { + avcodec_free_context(&codec_context_); + } if (frame_) { -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - av_free(frame_); - frame_ = NULL; -#else av_frame_free(&frame_); -#endif } if (io_buffer_) delete io_buffer_; @@ -111,15 +65,15 @@ void LibavStreamer::initialize(const cv::Mat &img) NULL, NULL); throw std::runtime_error("Error allocating ffmpeg format context"); } - output_format_ = av_guess_format(format_name_.c_str(), NULL, NULL); - if (!output_format_) + + format_context_->oformat = av_guess_format(format_name_.c_str(), NULL, NULL); + if (!format_context_->oformat) { async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_, connection_, NULL, NULL); throw std::runtime_error("Error looking up output format"); } - format_context_->oformat = output_format_; // Set up custom IO callback. size_t io_buffer_size = 3 * 1024; // 3M seen elsewhere and adjudged good @@ -134,12 +88,11 @@ void LibavStreamer::initialize(const cv::Mat &img) } io_ctx->seekable = 0; // no seeking, it's a stream format_context_->pb = io_ctx; - output_format_->flags |= AVFMT_FLAG_CUSTOM_IO; - output_format_->flags |= AVFMT_NOFILE; + format_context_->max_interleave_delta = 0; // Load codec if (codec_name_.empty()) // use default codec if none specified - codec_ = avcodec_find_encoder(output_format_->video_codec); + codec_ = avcodec_find_encoder(format_context_->oformat->video_codec); else codec_ = avcodec_find_encoder_by_name(codec_name_.c_str()); if (!codec_) @@ -157,11 +110,10 @@ void LibavStreamer::initialize(const cv::Mat &img) NULL, NULL); throw std::runtime_error("Error creating video stream"); } - codec_context_ = video_stream_->codec; - // Set options - avcodec_get_context_defaults3(codec_context_, codec_); + codec_context_ = avcodec_alloc_context3(codec_); + // Set options codec_context_->codec_id = codec_->id; codec_context_->bit_rate = bitrate_; @@ -182,11 +134,11 @@ void LibavStreamer::initialize(const cv::Mat &img) codec_context_->qmin = qmin_; codec_context_->qmax = qmax_; + codec_context_->flags |= AV_CODEC_FLAG_LOW_DELAY; + initializeEncoder(); - // Some formats want stream headers to be separate - if (format_context_->oformat->flags & AVFMT_GLOBALHEADER) - codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER; + avcodec_parameters_from_context(video_stream_->codecpar, codec_context_); // Open Codec if (avcodec_open2(codec_context_, codec_, NULL) < 0) @@ -198,23 +150,15 @@ void LibavStreamer::initialize(const cv::Mat &img) } // Allocate frame buffers -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - frame_ = avcodec_alloc_frame(); -#else frame_ = av_frame_alloc(); -#endif + av_image_alloc(frame_->data, frame_->linesize, output_width_, output_height_, codec_context_->pix_fmt, 1); frame_->width = output_width_; frame_->height = output_height_; frame_->format = codec_context_->pix_fmt; - output_format_->flags |= AVFMT_NOFILE; - // Generate header - std::vector header_buffer; - std::size_t header_size; - uint8_t *header_raw_buffer; // define meta data av_dict_set(&format_context_->metadata, "author", "ROS web_video_server", 0); av_dict_set(&format_context_->metadata, "title", topic_.c_str(), 0); @@ -247,23 +191,12 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) { first_image_timestamp_ = time; } - std::vector encoded_frame; -#if (LIBAVUTIL_VERSION_MAJOR < 53) - PixelFormat input_coding_format = PIX_FMT_BGR24; -#else + AVPixelFormat input_coding_format = AV_PIX_FMT_BGR24; -#endif -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - AVPicture *raw_frame = new AVPicture; - avpicture_fill(raw_frame, img.data, input_coding_format, output_width_, output_height_); -#else AVFrame *raw_frame = av_frame_alloc(); av_image_fill_arrays(raw_frame->data, raw_frame->linesize, img.data, input_coding_format, output_width_, output_height_, 1); -#endif - - // Convert from opencv to libav if (!sws_context_) @@ -282,41 +215,36 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) (const uint8_t * const *)raw_frame->data, raw_frame->linesize, 0, output_height_, frame_->data, frame_->linesize); -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - delete raw_frame; -#else av_frame_free(&raw_frame); -#endif // Encode the frame - AVPacket pkt; - int got_packet; - av_init_packet(&pkt); - -#if (LIBAVCODEC_VERSION_MAJOR < 54) - int buf_size = 6 * output_width_ * output_height_; - pkt.data = (uint8_t*)av_malloc(buf_size); - pkt.size = avcodec_encode_video(codec_context_, pkt.data, buf_size, frame_); - got_packet = pkt.size > 0; -#elif (LIBAVCODEC_VERSION_MAJOR < 57) - pkt.data = NULL; // packet data will be allocated by the encoder - pkt.size = 0; - if (avcodec_encode_video2(codec_context_, &pkt, frame_, &got_packet) < 0) + AVPacket* pkt = av_packet_alloc(); + + ret = avcodec_send_frame(codec_context_, frame_); + if (ret == AVERROR_EOF) { - throw std::runtime_error("Error encoding video frame"); + RCLCPP_DEBUG_STREAM(nh_->get_logger(), "avcodec_send_frame() encoder flushed\n"); } -#else - pkt.data = NULL; // packet data will be allocated by the encoder - pkt.size = 0; - if (avcodec_send_frame(codec_context_, frame_) < 0) + else if (ret == AVERROR(EAGAIN)) + { + RCLCPP_DEBUG_STREAM(nh_->get_logger(), "avcodec_send_frame() need output read out\n"); + } + if (ret < 0) { throw std::runtime_error("Error encoding video frame"); } - if (avcodec_receive_packet(codec_context_, &pkt) < 0) + + ret = avcodec_receive_packet(codec_context_, pkt); + bool got_packet = pkt->size > 0; + if (ret == AVERROR_EOF) + { + RCLCPP_DEBUG_STREAM(nh_->get_logger(), "avcodec_receive_packet() encoder flushed\n"); + } + else if (ret == AVERROR(EAGAIN)) { - throw std::runtime_error("Error retrieving encoded packet"); + RCLCPP_DEBUG_STREAM(nh_->get_logger(), "avcodec_receive_packet() needs more input\n"); + got_packet = false; } -#endif if (got_packet) { @@ -325,36 +253,23 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) double seconds = (time - first_image_timestamp_).seconds(); // Encode video at 1/0.95 to minimize delay - pkt.pts = (int64_t)(seconds / av_q2d(video_stream_->time_base) * 0.95); - if (pkt.pts <= 0) - pkt.pts = 1; - pkt.dts = AV_NOPTS_VALUE; + pkt->pts = (int64_t)(seconds / av_q2d(video_stream_->time_base) * 0.95); + if (pkt->pts <= 0) + pkt->pts = 1; + pkt->dts = pkt->pts; - if (pkt.flags&AV_PKT_FLAG_KEY) - pkt.flags |= AV_PKT_FLAG_KEY; + if (pkt->flags&AV_PKT_FLAG_KEY) + pkt->flags |= AV_PKT_FLAG_KEY; - pkt.stream_index = video_stream_->index; + pkt->stream_index = video_stream_->index; - if (av_write_frame(format_context_, &pkt)) + if (av_write_frame(format_context_, pkt)) { throw std::runtime_error("Error when writing frame"); } } - else - { - encoded_frame.clear(); - } -#if LIBAVCODEC_VERSION_INT < 54 - av_free(pkt.data); -#endif - -#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) - av_free_packet(&pkt); -#else - av_packet_unref(&pkt); -#endif - connection_->write_and_clear(encoded_frame); + av_packet_unref(pkt); } LibavStreamerType::LibavStreamerType(const std::string &format_name, const std::string &codec_name,