@@ -49,7 +49,7 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request,
49
49
const std::string &format_name, const std::string &codec_name,
50
50
const std::string &content_type) :
51
51
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_(
53
53
format_name), codec_name_(codec_name), content_type_(content_type)
54
54
{
55
55
@@ -72,22 +72,11 @@ LibavStreamer::~LibavStreamer()
72
72
av_free (frame_);
73
73
frame_ = NULL ;
74
74
#else
75
- avcodec_free_frame (&frame_);
75
+ av_frame_free (&frame_);
76
76
#endif
77
77
}
78
78
if (format_context_)
79
79
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
- }
91
80
if (sws_context_)
92
81
sws_freeContext (sws_context_);
93
82
}
@@ -151,7 +140,7 @@ void LibavStreamer::initialize(const cv::Mat &img)
151
140
codec_context_->time_base .num = 1 ;
152
141
codec_context_->time_base .den = 1 ;
153
142
codec_context_->gop_size = gop_;
154
- codec_context_->pix_fmt = PIX_FMT_YUV420P ;
143
+ codec_context_->pix_fmt = AV_PIX_FMT_YUV420P ;
155
144
codec_context_->max_b_frames = 0 ;
156
145
157
146
// Quality settings
@@ -174,18 +163,10 @@ void LibavStreamer::initialize(const cv::Mat &img)
174
163
}
175
164
176
165
// 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
+
189
170
190
171
output_format_->flags |= AVFMT_NOFILE;
191
172
@@ -241,9 +222,11 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
241
222
#if (LIBAVUTIL_VERSION_MAJOR < 52)
242
223
PixelFormat input_coding_format = PIX_FMT_BGR24;
243
224
#else
244
- AVPixelFormat input_coding_format = PIX_FMT_BGR24 ;
225
+ AVPixelFormat input_coding_format = AV_PIX_FMT_BGR24 ;
245
226
#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 );
247
230
248
231
// Convert from opencv to libav
249
232
if (!sws_context_)
@@ -257,8 +240,12 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
257
240
}
258
241
}
259
242
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);
262
249
263
250
// Encode the frame
264
251
AVPacket pkt;
@@ -270,13 +257,24 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
270
257
pkt.data = (uint8_t *)av_malloc (buf_size);
271
258
pkt.size = avcodec_encode_video (codec_context_, pkt.data , buf_size, frame_);
272
259
got_packet = pkt.size > 0 ;
273
- #else
260
+ #elif (LIBAVCODEC_VERSION_MAJOR < 57)
274
261
pkt.data = NULL ; // packet data will be allocated by the encoder
275
262
pkt.size = 0 ;
276
263
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 )
277
271
{
278
272
throw std::runtime_error (" Error encoding video frame" );
279
273
}
274
+ if (avcodec_receive_packet (codec_context_, &pkt) < 0 )
275
+ {
276
+ throw std::runtime_error (" Error retrieving encoded packet" );
277
+ }
280
278
#endif
281
279
282
280
if (got_packet)
@@ -291,7 +289,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
291
289
pkt.pts = 1 ;
292
290
pkt.dts = AV_NOPTS_VALUE;
293
291
294
- if (codec_context_-> coded_frame -> key_frame )
292
+ if (pkt. flags &AV_PKT_FLAG_KEY )
295
293
pkt.flags |= AV_PKT_FLAG_KEY;
296
294
297
295
pkt.stream_index = video_stream_->index ;
@@ -318,7 +316,7 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
318
316
av_free (pkt.data );
319
317
#endif
320
318
321
- av_free_packet (&pkt);
319
+ av_packet_unref (&pkt);
322
320
323
321
connection_->write_and_clear (encoded_frame);
324
322
}
0 commit comments