Skip to content

Commit dfc4bf0

Browse files
authored
fix vp9 and h264, support for opencv4 and ffmpeg 4 (#103)
1 parent b3b367d commit dfc4bf0

File tree

6 files changed

+61
-15
lines changed

6 files changed

+61
-15
lines changed

include/web_video_server/jpeg_streamers.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
#define JPEG_STREAMERS_H_
33

44
#include <image_transport/image_transport.h>
5+
#include <opencv2/imgcodecs.hpp>
56
#include "web_video_server/image_streamer.h"
67
#include "async_web_server_cpp/http_request.hpp"
78
#include "async_web_server_cpp/http_connection.hpp"

include/web_video_server/png_streamers.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
#define PNG_STREAMERS_H_
33

44
#include <image_transport/image_transport.h>
5+
#include <opencv2/imgcodecs.hpp>
56
#include "web_video_server/image_streamer.h"
67
#include "async_web_server_cpp/http_request.hpp"
78
#include "async_web_server_cpp/http_connection.hpp"

src/image_streamer.cpp

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -112,10 +112,9 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr
112112
int input_width = img.cols;
113113
int input_height = img.rows;
114114

115-
if (output_width_ == -1)
116-
output_width_ = input_width;
117-
if (output_height_ == -1)
118-
output_height_ = input_height;
115+
116+
output_width_ = input_width;
117+
output_height_ = input_height;
119118

120119
if (invert_)
121120
{
@@ -144,8 +143,7 @@ void ImageTransportImageStreamer::imageCallback(const sensor_msgs::ImageConstPtr
144143
}
145144

146145
last_frame = ros::Time::now();
147-
sendImage(output_size_image, last_frame );
148-
146+
sendImage(output_size_image, msg->header.stamp);
149147
}
150148
catch (cv_bridge::Exception &e)
151149
{

src/jpeg_streamers.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,11 @@ MjpegStreamer::~MjpegStreamer()
2121
void MjpegStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
2222
{
2323
std::vector<int> encode_params;
24+
#if CV_VERSION_MAJOR >= 3
25+
encode_params.push_back(cv::IMWRITE_JPEG_QUALITY);
26+
#else
2427
encode_params.push_back(CV_IMWRITE_JPEG_QUALITY);
28+
#endif
2529
encode_params.push_back(quality_);
2630

2731
std::vector<uchar> encoded_buffer;
@@ -63,7 +67,11 @@ JpegSnapshotStreamer::~JpegSnapshotStreamer()
6367
void JpegSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
6468
{
6569
std::vector<int> encode_params;
70+
#if CV_VERSION_MAJOR >= 3
71+
encode_params.push_back(cv::IMWRITE_JPEG_QUALITY);
72+
#else
6673
encode_params.push_back(CV_IMWRITE_JPEG_QUALITY);
74+
#endif
6775
encode_params.push_back(quality_);
6876

6977
std::vector<uchar> encoded_buffer;

src/libav_streamer.cpp

Lines changed: 39 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -60,16 +60,24 @@ LibavStreamer::LibavStreamer(const async_web_server_cpp::HttpRequest &request,
6060
bitrate_ = request.get_query_param_value_or_default<int>("bitrate", 100000);
6161
qmin_ = request.get_query_param_value_or_default<int>("qmin", 10);
6262
qmax_ = request.get_query_param_value_or_default<int>("qmax", 42);
63-
gop_ = request.get_query_param_value_or_default<int>("gop", 250);
63+
gop_ = request.get_query_param_value_or_default<int>("gop", 25);
6464

65+
#if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) )
6566
av_lockmgr_register(&ffmpeg_boost_mutex_lock_manager);
6667
av_register_all();
68+
#endif
6769
}
6870

6971
LibavStreamer::~LibavStreamer()
7072
{
7173
if (codec_context_)
74+
{
75+
#if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) )
7276
avcodec_close(codec_context_);
77+
#else
78+
avcodec_free_context(&codec_context_);
79+
#endif
80+
}
7381
if (frame_)
7482
{
7583
#if LIBAVCODEC_VERSION_INT < AV_VERSION_INT(55,28,1)
@@ -134,6 +142,7 @@ void LibavStreamer::initialize(const cv::Mat &img)
134142
}
135143
io_ctx->seekable = 0; // no seeking, it's a stream
136144
format_context_->pb = io_ctx;
145+
format_context_->max_interleave_delta = 0;
137146
output_format_->flags |= AVFMT_FLAG_CUSTOM_IO;
138147
output_format_->flags |= AVFMT_NOFILE;
139148

@@ -157,7 +166,11 @@ void LibavStreamer::initialize(const cv::Mat &img)
157166
NULL, NULL);
158167
throw std::runtime_error("Error creating video stream");
159168
}
169+
#if ( LIBAVCODEC_VERSION_INT < AV_VERSION_INT(58,9,100) )
160170
codec_context_ = video_stream_->codec;
171+
#else
172+
codec_context_ = avcodec_alloc_context3(codec_);
173+
#endif
161174

162175
// Set options
163176
avcodec_get_context_defaults3(codec_context_, codec_);
@@ -182,11 +195,14 @@ void LibavStreamer::initialize(const cv::Mat &img)
182195
codec_context_->qmin = qmin_;
183196
codec_context_->qmax = qmax_;
184197

198+
#if ( LIBAVCODEC_VERSION_INT >= AV_VERSION_INT(58,9,100) )
199+
avcodec_parameters_from_context(video_stream_->codecpar, codec_context_);
200+
#endif
201+
185202
initializeEncoder();
186203

187-
// Some formats want stream headers to be separate
188-
if (format_context_->oformat->flags & AVFMT_GLOBALHEADER)
189-
codec_context_->flags |= CODEC_FLAG_GLOBAL_HEADER;
204+
codec_context_->flags |= AV_CODEC_FLAG_LOW_DELAY;
205+
codec_context_->max_b_frames = 0;
190206

191207
// Open Codec
192208
if (avcodec_open2(codec_context_, codec_, NULL) < 0)
@@ -306,15 +322,29 @@ void LibavStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
306322
throw std::runtime_error("Error encoding video frame");
307323
}
308324
#else
309-
pkt.data = NULL; // packet data will be allocated by the encoder
310-
pkt.size = 0;
311-
if (avcodec_send_frame(codec_context_, frame_) < 0)
325+
ret = avcodec_send_frame(codec_context_, frame_);
326+
if (ret == AVERROR_EOF)
327+
{
328+
ROS_DEBUG_STREAM("avcodec_send_frame() encoder flushed");
329+
}
330+
else if (ret == AVERROR(EAGAIN))
331+
{
332+
ROS_DEBUG_STREAM("avcodec_send_frame() need output read out");
333+
}
334+
if (ret < 0)
312335
{
313336
throw std::runtime_error("Error encoding video frame");
314337
}
315-
if (avcodec_receive_packet(codec_context_, &pkt) < 0)
338+
ret = avcodec_receive_packet(codec_context_, &pkt);
339+
got_packet = pkt.size > 0;
340+
if (ret == AVERROR_EOF)
341+
{
342+
ROS_DEBUG_STREAM("avcodec_recieve_packet() encoder flushed");
343+
}
344+
else if (ret == AVERROR(EAGAIN))
316345
{
317-
throw std::runtime_error("Error retrieving encoded packet");
346+
ROS_DEBUG_STREAM("avcodec_recieve_packet() need more input");
347+
got_packet = 0;
318348
}
319349
#endif
320350

src/png_streamers.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,11 @@ PngStreamer::~PngStreamer()
2121
void PngStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
2222
{
2323
std::vector<int> encode_params;
24+
#if CV_VERSION_MAJOR >= 3
25+
encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION);
26+
#else
2427
encode_params.push_back(CV_IMWRITE_PNG_COMPRESSION);
28+
#endif
2529
encode_params.push_back(quality_);
2630

2731
std::vector<uchar> encoded_buffer;
@@ -63,7 +67,11 @@ PngSnapshotStreamer::~PngSnapshotStreamer()
6367
void PngSnapshotStreamer::sendImage(const cv::Mat &img, const ros::Time &time)
6468
{
6569
std::vector<int> encode_params;
70+
#if CV_VERSION_MAJOR >= 3
71+
encode_params.push_back(cv::IMWRITE_PNG_COMPRESSION);
72+
#else
6673
encode_params.push_back(CV_IMWRITE_PNG_COMPRESSION);
74+
#endif
6775
encode_params.push_back(quality_);
6876

6977
std::vector<uchar> encoded_buffer;

0 commit comments

Comments
 (0)