From d2720fd06b535ef57931799cbb3a5489c0f9aeaa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 30 Sep 2024 17:30:31 +0200 Subject: [PATCH 1/9] Fix usage of deprecated libavcodec functions --- include/web_video_server/libav_streamer.h | 4 +- src/libav_streamer.cpp | 93 ++++++----------------- 2 files changed, 27 insertions(+), 70 deletions(-) diff --git a/include/web_video_server/libav_streamer.h b/include/web_video_server/libav_streamer.h index 643e3b3..f5a1ebc 100644 --- a/include/web_video_server/libav_streamer.h +++ b/include/web_video_server/libav_streamer.h @@ -34,9 +34,9 @@ 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_; + AVOutputFormat output_format_; AVFormatContext* format_context_; - AVCodec* codec_; + const AVCodec* codec_; AVCodecContext* codec_context_; AVStream* video_stream_; diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 28d0425..b557bc4 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) { @@ -61,9 +21,6 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request, 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(); } LibavStreamer::~LibavStreamer() @@ -111,15 +68,18 @@ 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_) + const AVOutputFormat* guessed_format = av_guess_format(format_name_.c_str(), NULL, NULL); + if (!guessed_format) { 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_; + + + output_format_ = *guessed_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 +94,12 @@ 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; + output_format_.flags |= AVFMT_FLAG_CUSTOM_IO; + output_format_.flags |= AVFMT_NOFILE; // Load codec if (codec_name_.empty()) // use default codec if none specified - codec_ = avcodec_find_encoder(output_format_->video_codec); + codec_ = avcodec_find_encoder(output_format_.video_codec); else codec_ = avcodec_find_encoder_by_name(codec_name_.c_str()); if (!codec_) @@ -157,11 +117,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_; @@ -209,7 +168,7 @@ void LibavStreamer::initialize(const cv::Mat &img) frame_->width = output_width_; frame_->height = output_height_; frame_->format = codec_context_->pix_fmt; - output_format_->flags |= AVFMT_NOFILE; + output_format_.flags |= AVFMT_NOFILE; // Generate header std::vector header_buffer; @@ -289,9 +248,8 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) #endif // Encode the frame - AVPacket pkt; + AVPacket* pkt = av_packet_alloc(); int got_packet; - av_init_packet(&pkt); #if (LIBAVCODEC_VERSION_MAJOR < 54) int buf_size = 6 * output_width_ * output_height_; @@ -306,16 +264,15 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) throw std::runtime_error("Error encoding video frame"); } #else - pkt.data = NULL; // packet data will be allocated by the encoder - pkt.size = 0; if (avcodec_send_frame(codec_context_, frame_) < 0) { throw std::runtime_error("Error encoding video frame"); } - if (avcodec_receive_packet(codec_context_, &pkt) < 0) + if (avcodec_receive_packet(codec_context_, pkt) < 0) { throw std::runtime_error("Error retrieving encoded packet"); } + got_packet = pkt->size > 0; #endif if (got_packet) @@ -325,17 +282,17 @@ 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 = AV_NOPTS_VALUE; - 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"); } @@ -351,7 +308,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) #if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1) av_free_packet(&pkt); #else - av_packet_unref(&pkt); + av_packet_unref(pkt); #endif connection_->write_and_clear(encoded_frame); From 288d87a632e3b319c4d154fea4146e43c7546115 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 30 Sep 2024 17:39:06 +0200 Subject: [PATCH 2/9] Drop compatibility with old ffmpeg libraries --- src/libav_streamer.cpp | 53 ++++-------------------------------------- 1 file changed, 4 insertions(+), 49 deletions(-) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index b557bc4..1b81764 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -29,12 +29,7 @@ LibavStreamer::~LibavStreamer() avcodec_close(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_; @@ -157,11 +152,8 @@ 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); @@ -207,22 +199,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_) @@ -241,29 +223,11 @@ 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 = av_packet_alloc(); - int got_packet; - -#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) - { - throw std::runtime_error("Error encoding video frame"); - } -#else + if (avcodec_send_frame(codec_context_, frame_) < 0) { throw std::runtime_error("Error encoding video frame"); @@ -272,10 +236,8 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) { throw std::runtime_error("Error retrieving encoded packet"); } - got_packet = pkt->size > 0; -#endif - if (got_packet) + if (pkt->size > 0) { std::size_t size; uint8_t *output_buf; @@ -301,15 +263,8 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) { 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); } From 2c8316ba842cb46da933de6419caf502f61a3568 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 30 Sep 2024 18:57:31 +0200 Subject: [PATCH 3/9] backport #103 --- src/image_streamer.cpp | 10 ++++----- src/libav_streamer.cpp | 46 ++++++++++++++++++++++++++++++++++-------- 2 files changed, 42 insertions(+), 14 deletions(-) diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index 9309be8..d141bf4 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -139,10 +139,9 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C int input_width = img.cols; int input_height = img.rows; - if (output_width_ == -1) - output_width_ = input_width; - if (output_height_ == -1) - output_height_ = input_height; + + output_width_ = input_width; + output_height_ = input_height; if (invert_) { @@ -171,8 +170,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 1b81764..d913e11 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -20,13 +20,19 @@ 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); + gop_ = request.get_query_param_value_or_default("gop", 25); } LibavStreamer::~LibavStreamer() { if (codec_context_) + { + #if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) ) avcodec_close(codec_context_); + #else + avcodec_free_context(&codec_context_); + #endif + } if (frame_) { av_frame_free(&frame_); @@ -89,6 +95,7 @@ void LibavStreamer::initialize(const cv::Mat &img) } io_ctx->seekable = 0; // no seeking, it's a stream format_context_->pb = io_ctx; + format_context_->max_interleave_delta = 0; output_format_.flags |= AVFMT_FLAG_CUSTOM_IO; output_format_.flags |= AVFMT_NOFILE; @@ -136,11 +143,12 @@ void LibavStreamer::initialize(const cv::Mat &img) codec_context_->qmin = qmin_; codec_context_->qmax = qmax_; + avcodec_parameters_from_context(video_stream_->codecpar, codec_context_); + initializeEncoder(); - // Some formats want stream headers to be separate - if (format_context_->oformat->flags & AVFMT_GLOBALHEADER) - codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER; + codec_context_->flags |= AV_CODEC_FLAG_LOW_DELAY; + codec_context_->max_b_frames = 0; // Open Codec if (avcodec_open2(codec_context_, codec_, NULL) < 0) @@ -228,16 +236,38 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) // Encode the frame AVPacket* pkt = av_packet_alloc(); - if (avcodec_send_frame(codec_context_, frame_) < 0) + ret = avcodec_send_frame(codec_context_, frame_); + if (ret == AVERROR_EOF) + { + std::cerr << "avcodec_send_frame() encoder flushed\n"; + // ROS_DEBUG_STREAM("avcodec_send_frame() encoder flushed"); + } + else if (ret == AVERROR(EAGAIN)) { + std::cerr << "avcodec_send_frame() need output read out\n"; + // ROS_DEBUG_STREAM("avcodec_send_frame() need output read out"); + } + if (ret < 0) + { + // std::cerr << "Error encoding video frame\n"; 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) + { + std::cerr << "avcodec_recieve_packet() encoder flushed\n"; + // ROS_DEBUG_STREAM("avcodec_recieve_packet() encoder flushed"); + } + else if (ret == AVERROR(EAGAIN)) { - throw std::runtime_error("Error retrieving encoded packet"); + std::cerr << "avcodec_recieve_packet() need more input\n"; + // ROS_DEBUG_STREAM("avcodec_recieve_packet() need more input"); + got_packet = false; } - if (pkt->size > 0) + if (got_packet) { std::size_t size; uint8_t *output_buf; From 09801e0a840eb1e1181820e62343dcc7ba4f7ac9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Mon, 30 Sep 2024 23:43:36 +0000 Subject: [PATCH 4/9] Remove remaining avcodec version check --- src/libav_streamer.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index d913e11..3bb54e1 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -27,11 +27,7 @@ LibavStreamer::~LibavStreamer() { if (codec_context_) { - #if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) ) - avcodec_close(codec_context_); - #else avcodec_free_context(&codec_context_); - #endif } if (frame_) { From 7790236b9b48497859c4528b7eca94c3397b398d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Tue, 1 Oct 2024 10:57:54 +0000 Subject: [PATCH 5/9] Use rclcpp debug logs instead of cerr --- src/libav_streamer.cpp | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 3bb54e1..df1e3d8 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -235,17 +235,14 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) ret = avcodec_send_frame(codec_context_, frame_); if (ret == AVERROR_EOF) { - std::cerr << "avcodec_send_frame() encoder flushed\n"; - // ROS_DEBUG_STREAM("avcodec_send_frame() encoder flushed"); + RCLCPP_DEBUG_STREAM(nh_->get_logger(), "avcodec_send_frame() encoder flushed\n"); } else if (ret == AVERROR(EAGAIN)) { - std::cerr << "avcodec_send_frame() need output read out\n"; - // ROS_DEBUG_STREAM("avcodec_send_frame() need output read out"); + RCLCPP_DEBUG_STREAM(nh_->get_logger(), "avcodec_send_frame() need output read out\n"); } if (ret < 0) { - // std::cerr << "Error encoding video frame\n"; throw std::runtime_error("Error encoding video frame"); } @@ -253,13 +250,11 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) bool got_packet = pkt->size > 0; if (ret == AVERROR_EOF) { - std::cerr << "avcodec_recieve_packet() encoder flushed\n"; - // ROS_DEBUG_STREAM("avcodec_recieve_packet() encoder flushed"); + RCLCPP_DEBUG_STREAM(nh_->get_logger(), "avcodec_receive_packet() encoder flushed\n"); } else if (ret == AVERROR(EAGAIN)) { - std::cerr << "avcodec_recieve_packet() need more input\n"; - // ROS_DEBUG_STREAM("avcodec_recieve_packet() need more input"); + RCLCPP_DEBUG_STREAM(nh_->get_logger(), "avcodec_receive_packet() needs more input\n"); got_packet = false; } From 2bb2726fa858cbf594a20996a9a1c8656d202c6b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Tue, 1 Oct 2024 11:20:20 +0000 Subject: [PATCH 6/9] Remove redundant vector --- src/libav_streamer.cpp | 7 ------- 1 file changed, 7 deletions(-) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index df1e3d8..ddb279c 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -202,7 +202,6 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) { first_image_timestamp_ = time; } - std::vector encoded_frame; AVPixelFormat input_coding_format = AV_PIX_FMT_BGR24; @@ -280,14 +279,8 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) throw std::runtime_error("Error when writing frame"); } } - else - { - encoded_frame.clear(); - } av_packet_unref(pkt); - - connection_->write_and_clear(encoded_frame); } LibavStreamerType::LibavStreamerType(const std::string &format_name, const std::string &codec_name, From 916e06de915ebdd980d27fc64cae122ae0d7dd7e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Tue, 1 Oct 2024 15:34:30 +0200 Subject: [PATCH 7/9] Fix segfault on write_header --- include/web_video_server/libav_streamer.h | 1 - src/libav_streamer.cpp | 23 ++++++----------------- 2 files changed, 6 insertions(+), 18 deletions(-) diff --git a/include/web_video_server/libav_streamer.h b/include/web_video_server/libav_streamer.h index f5a1ebc..635be1c 100644 --- a/include/web_video_server/libav_streamer.h +++ b/include/web_video_server/libav_streamer.h @@ -34,7 +34,6 @@ 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_; const AVCodec* codec_; AVCodecContext* codec_context_; diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index ddb279c..9330daf 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -65,8 +65,9 @@ void LibavStreamer::initialize(const cv::Mat &img) NULL, NULL); throw std::runtime_error("Error allocating ffmpeg format context"); } - const AVOutputFormat* guessed_format = av_guess_format(format_name_.c_str(), NULL, NULL); - if (!guessed_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_, @@ -74,10 +75,6 @@ void LibavStreamer::initialize(const cv::Mat &img) throw std::runtime_error("Error looking up output format"); } - - output_format_ = *guessed_format; - format_context_->oformat = &output_format_; - // Set up custom IO callback. size_t io_buffer_size = 3 * 1024; // 3M seen elsewhere and adjudged good io_buffer_ = new unsigned char[io_buffer_size]; @@ -92,12 +89,10 @@ void LibavStreamer::initialize(const cv::Mat &img) io_ctx->seekable = 0; // no seeking, it's a stream format_context_->pb = io_ctx; format_context_->max_interleave_delta = 0; - output_format_.flags |= AVFMT_FLAG_CUSTOM_IO; - output_format_.flags |= AVFMT_NOFILE; // 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_) @@ -139,12 +134,11 @@ void LibavStreamer::initialize(const cv::Mat &img) codec_context_->qmin = qmin_; codec_context_->qmax = qmax_; - avcodec_parameters_from_context(video_stream_->codecpar, codec_context_); + codec_context_->flags |= AV_CODEC_FLAG_LOW_DELAY; initializeEncoder(); - codec_context_->flags |= AV_CODEC_FLAG_LOW_DELAY; - codec_context_->max_b_frames = 0; + avcodec_parameters_from_context(video_stream_->codecpar, codec_context_); // Open Codec if (avcodec_open2(codec_context_, codec_, NULL) < 0) @@ -164,12 +158,7 @@ void LibavStreamer::initialize(const cv::Mat &img) 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); From 2b8f98b6dfb3de98c1843cdeb0ccee37a9043e19 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Tue, 1 Oct 2024 13:40:54 +0000 Subject: [PATCH 8/9] Allow overriding width and height --- src/image_streamer.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/image_streamer.cpp b/src/image_streamer.cpp index d141bf4..a91c31a 100644 --- a/src/image_streamer.cpp +++ b/src/image_streamer.cpp @@ -139,9 +139,10 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C int input_width = img.cols; int input_height = img.rows; - - output_width_ = input_width; - output_height_ = input_height; + if (output_width_ == -1) + output_width_ = input_width; + if (output_height_ == -1) + output_height_ = input_height; if (invert_) { From 524903da511f09fa220d3754145092e735efc7f4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?B=C5=82a=C5=BCej=20Sowa?= Date: Tue, 1 Oct 2024 14:57:27 +0000 Subject: [PATCH 9/9] Fix warning about missing timestamps --- src/libav_streamer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/libav_streamer.cpp b/src/libav_streamer.cpp index 9330daf..0e490ac 100644 --- a/src/libav_streamer.cpp +++ b/src/libav_streamer.cpp @@ -256,7 +256,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time) 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->dts = pkt->pts; if (pkt->flags&AV_PKT_FLAG_KEY) pkt->flags |= AV_PKT_FLAG_KEY;