Skip to content

Commit 2c8316b

Browse files
committed
backport #103
1 parent 288d87a commit 2c8316b

File tree

2 files changed

+42
-14
lines changed

2 files changed

+42
-14
lines changed

src/image_streamer.cpp

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -139,10 +139,9 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C
139139
int input_width = img.cols;
140140
int input_height = img.rows;
141141

142-
if (output_width_ == -1)
143-
output_width_ = input_width;
144-
if (output_height_ == -1)
145-
output_height_ = input_height;
142+
143+
output_width_ = input_width;
144+
output_height_ = input_height;
146145

147146
if (invert_)
148147
{
@@ -171,8 +170,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::msg::Image::C
171170
}
172171

173172
last_frame = nh_->now();
174-
sendImage(output_size_image, last_frame );
175-
173+
sendImage(output_size_image, msg->header.stamp);
176174
}
177175
catch (cv_bridge::Exception &e)
178176
{

src/libav_streamer.cpp

Lines changed: 38 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -20,13 +20,19 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request,
2020
bitrate_ = request.get_query_param_value_or_default<int>("bitrate", 100000);
2121
qmin_ = request.get_query_param_value_or_default<int>("qmin", 10);
2222
qmax_ = request.get_query_param_value_or_default<int>("qmax", 42);
23-
gop_ = request.get_query_param_value_or_default<int>("gop", 250);
23+
gop_ = request.get_query_param_value_or_default<int>("gop", 25);
2424
}
2525

2626
LibavStreamer::~LibavStreamer()
2727
{
2828
if (codec_context_)
29+
{
30+
#if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) )
2931
avcodec_close(codec_context_);
32+
#else
33+
avcodec_free_context(&codec_context_);
34+
#endif
35+
}
3036
if (frame_)
3137
{
3238
av_frame_free(&frame_);
@@ -89,6 +95,7 @@ void LibavStreamer::initialize(const cv::Mat &img)
8995
}
9096
io_ctx->seekable = 0; // no seeking, it's a stream
9197
format_context_->pb = io_ctx;
98+
format_context_->max_interleave_delta = 0;
9299
output_format_.flags |= AVFMT_FLAG_CUSTOM_IO;
93100
output_format_.flags |= AVFMT_NOFILE;
94101

@@ -136,11 +143,12 @@ void LibavStreamer::initialize(const cv::Mat &img)
136143
codec_context_->qmin = qmin_;
137144
codec_context_->qmax = qmax_;
138145

146+
avcodec_parameters_from_context(video_stream_->codecpar, codec_context_);
147+
139148
initializeEncoder();
140149

141-
// Some formats want stream headers to be separate
142-
if (format_context_->oformat->flags & AVFMT_GLOBALHEADER)
143-
codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER;
150+
codec_context_->flags |= AV_CODEC_FLAG_LOW_DELAY;
151+
codec_context_->max_b_frames = 0;
144152

145153
// Open Codec
146154
if (avcodec_open2(codec_context_, codec_, NULL) < 0)
@@ -228,16 +236,38 @@ void LibavStreamer::sendImage(const cv::Mat &img, const rclcpp::Time &time)
228236
// Encode the frame
229237
AVPacket* pkt = av_packet_alloc();
230238

231-
if (avcodec_send_frame(codec_context_, frame_) < 0)
239+
ret = avcodec_send_frame(codec_context_, frame_);
240+
if (ret == AVERROR_EOF)
241+
{
242+
std::cerr << "avcodec_send_frame() encoder flushed\n";
243+
// ROS_DEBUG_STREAM("avcodec_send_frame() encoder flushed");
244+
}
245+
else if (ret == AVERROR(EAGAIN))
232246
{
247+
std::cerr << "avcodec_send_frame() need output read out\n";
248+
// ROS_DEBUG_STREAM("avcodec_send_frame() need output read out");
249+
}
250+
if (ret < 0)
251+
{
252+
// std::cerr << "Error encoding video frame\n";
233253
throw std::runtime_error("Error encoding video frame");
234254
}
235-
if (avcodec_receive_packet(codec_context_, pkt) < 0)
255+
256+
ret = avcodec_receive_packet(codec_context_, pkt);
257+
bool got_packet = pkt->size > 0;
258+
if (ret == AVERROR_EOF)
259+
{
260+
std::cerr << "avcodec_recieve_packet() encoder flushed\n";
261+
// ROS_DEBUG_STREAM("avcodec_recieve_packet() encoder flushed");
262+
}
263+
else if (ret == AVERROR(EAGAIN))
236264
{
237-
throw std::runtime_error("Error retrieving encoded packet");
265+
std::cerr << "avcodec_recieve_packet() need more input\n";
266+
// ROS_DEBUG_STREAM("avcodec_recieve_packet() need more input");
267+
got_packet = false;
238268
}
239269

240-
if (pkt->size > 0)
270+
if (got_packet)
241271
{
242272
std::size_t size;
243273
uint8_t *output_buf;

0 commit comments

Comments
 (0)