Skip to content

Commit a9dff84

Browse files
russelhowejihoonl
authored andcommitted
Ffmpeg 3 (#43)
* Correct use of deprecated parameters codec_context_->rc_buffer_aggressivity marked as "currently useless", so removed codec_context_->frame_skip_threshold access through new priv_data api * New names for pixel formats * AVPicture is deprecated, use AVFrame * Switch to non-deprecated free functions * Use new encoding api for newer versions encode_video2 is deprecated * codec_context is deprecated, use packet flags
1 parent 3f7ffeb commit a9dff84

File tree

3 files changed

+33
-37
lines changed

3 files changed

+33
-37
lines changed

include/web_video_server/libav_streamer.h

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ extern "C"
1515
#include <libswscale/swscale.h>
1616
#include <libavutil/opt.h>
1717
#include <libavutil/mathematics.h>
18+
#include <libavutil/imgutils.h>
1819
}
1920

2021
namespace web_video_server
@@ -41,8 +42,6 @@ class LibavStreamer : public ImageTransportImageStreamer
4142

4243
private:
4344
AVFrame* frame_;
44-
AVPicture* picture_;
45-
AVPicture* tmp_picture_;
4645
struct SwsContext* sws_context_;
4746
ros::Time first_image_timestamp_;
4847
boost::mutex encode_mutex_;

src/libav_streamer.cpp

Lines changed: 31 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request,
4949
const std::string &format_name, const std::string &codec_name,
5050
const std::string &content_type) :
5151
ImageTransportImageStreamer(request, connection, nh), output_format_(0), format_context_(0), codec_(0), codec_context_(0), video_stream_(
52-
0), frame_(0), picture_(0), tmp_picture_(0), sws_context_(0), first_image_timestamp_(0), format_name_(
52+
0), frame_(0), sws_context_(0), first_image_timestamp_(0), format_name_(
5353
format_name), codec_name_(codec_name), content_type_(content_type)
5454
{
5555

@@ -72,22 +72,11 @@ LibavStreamer::~LibavStreamer()
7272
av_free(frame_);
7373
frame_ = NULL;
7474
#else
75-
avcodec_free_frame(&frame_);
75+
av_frame_free(&frame_);
7676
#endif
7777
}
7878
if (format_context_)
7979
avformat_free_context(format_context_);
80-
if (picture_)
81-
{
82-
avpicture_free(picture_);
83-
delete picture_;
84-
picture_ = NULL;
85-
}
86-
if (tmp_picture_)
87-
{
88-
delete tmp_picture_;
89-
tmp_picture_ = NULL;
90-
}
9180
if (sws_context_)
9281
sws_freeContext(sws_context_);
9382
}
@@ -151,7 +140,7 @@ void LibavStreamer::initialize(const cv::Mat &img)
151140
codec_context_->time_base.num = 1;
152141
codec_context_->time_base.den = 1;
153142
codec_context_->gop_size = gop_;
154-
codec_context_->pix_fmt = PIX_FMT_YUV420P;
143+
codec_context_->pix_fmt = AV_PIX_FMT_YUV420P;
155144
codec_context_->max_b_frames = 0;
156145

157146
// Quality settings
@@ -174,18 +163,10 @@ void LibavStreamer::initialize(const cv::Mat &img)
174163
}
175164

176165
// Allocate frame buffers
177-
frame_ = avcodec_alloc_frame();
178-
tmp_picture_ = new AVPicture;
179-
picture_ = new AVPicture;
180-
int ret = avpicture_alloc(picture_, codec_context_->pix_fmt, output_width_, output_height_);
181-
if (ret < 0)
182-
{
183-
async_web_server_cpp::HttpReply::stock_reply(async_web_server_cpp::HttpReply::internal_server_error)(request_,
184-
connection_,
185-
NULL, NULL);
186-
throw std::runtime_error("Could not allocate picture frame");
187-
}
188-
*((AVPicture *)frame_) = *picture_;
166+
frame_ = av_frame_alloc();
167+
av_image_alloc(frame_->data, frame_->linesize, output_width_, output_height_,
168+
codec_context_->pix_fmt, 1);
169+
189170

190171
output_format_->flags |= AVFMT_NOFILE;
191172

@@ -241,9 +222,11 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
241222
#if (LIBAVUTIL_VERSION_MAJOR < 52)
242223
PixelFormat input_coding_format = PIX_FMT_BGR24;
243224
#else
244-
AVPixelFormat input_coding_format = PIX_FMT_BGR24;
225+
AVPixelFormat input_coding_format = AV_PIX_FMT_BGR24;
245226
#endif
246-
avpicture_fill(tmp_picture_, img.data, input_coding_format, output_width_, output_height_);
227+
AVFrame *raw_frame = av_frame_alloc();
228+
av_image_fill_arrays(raw_frame->data, raw_frame->linesize,
229+
img.data, input_coding_format, output_width_, output_height_, 0);
247230

248231
// Convert from opencv to libav
249232
if (!sws_context_)
@@ -257,8 +240,12 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
257240
}
258241
}
259242

260-
int ret = sws_scale(sws_context_, (const uint8_t * const *)tmp_picture_->data, tmp_picture_->linesize, 0,
261-
output_height_, picture_->data, picture_->linesize);
243+
244+
int ret = sws_scale(sws_context_,
245+
(const uint8_t * const *)raw_frame->data, raw_frame->linesize, 0,
246+
output_height_, frame_->data, frame_->linesize);
247+
248+
av_frame_free(&raw_frame);
262249

263250
// Encode the frame
264251
AVPacket pkt;
@@ -270,13 +257,24 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
270257
pkt.data = (uint8_t*)av_malloc(buf_size);
271258
pkt.size = avcodec_encode_video(codec_context_, pkt.data, buf_size, frame_);
272259
got_packet = pkt.size > 0;
273-
#else
260+
#elif (LIBAVCODEC_VERSION_MAJOR < 57)
274261
pkt.data = NULL; // packet data will be allocated by the encoder
275262
pkt.size = 0;
276263
if (avcodec_encode_video2(codec_context_, &pkt, frame_, &got_packet) < 0)
264+
{
265+
throw std::runtime_error("Error encoding video frame");
266+
}
267+
#else
268+
pkt.data = NULL; // packet data will be allocated by the encoder
269+
pkt.size = 0;
270+
if (avcodec_send_frame(codec_context_, frame_) < 0)
277271
{
278272
throw std::runtime_error("Error encoding video frame");
279273
}
274+
if (avcodec_receive_packet(codec_context_, &pkt) < 0)
275+
{
276+
throw std::runtime_error("Error retrieving encoded packet");
277+
}
280278
#endif
281279

282280
if (got_packet)
@@ -291,7 +289,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
291289
pkt.pts = 1;
292290
pkt.dts = AV_NOPTS_VALUE;
293291

294-
if (codec_context_->coded_frame->key_frame)
292+
if (pkt.flags&AV_PKT_FLAG_KEY)
295293
pkt.flags |= AV_PKT_FLAG_KEY;
296294

297295
pkt.stream_index = video_stream_->index;
@@ -318,7 +316,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
318316
av_free(pkt.data);
319317
#endif
320318

321-
av_free_packet(&pkt);
319+
av_packet_unref(&pkt);
322320

323321
connection_->write_and_clear(encoded_frame);
324322
}

src/vp8_streamer.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -73,8 +73,7 @@ void Vp8Streamer::initializeEncoder()
7373
av_opt_set_int(codec_context_->priv_data, "bufsize", bufsize, 0);
7474
av_opt_set_int(codec_context_->priv_data, "buf-initial", bufsize, 0);
7575
av_opt_set_int(codec_context_->priv_data, "buf-optimal", bufsize, 0);
76-
codec_context_->rc_buffer_aggressivity = 0.5;
77-
codec_context_->frame_skip_threshold = 10;
76+
av_opt_set_int(codec_context_->priv_data, "skip_threshold", 10, 0);
7877
}
7978

8079
Vp8StreamerType::Vp8StreamerType() :

0 commit comments

Comments
 (0)