Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added SVTAV1 image transport plugin #161

Draft
wants to merge 6 commits into
base: rolling
Choose a base branch
from
Draft
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Prev Previous commit
Next Next commit
Added params
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
ahcorde committed Dec 5, 2023
commit 116383c78bfd1b74fec2285cf8625cb2ad3e288a
26 changes: 11 additions & 15 deletions svtav1_image_transport/src/svtav1_publisher.cpp
Original file line number Diff line number Diff line change
@@ -49,7 +49,7 @@ const struct ParameterDefinition kParameters[] =
{
{
// ENC mode - SVTAV1 Compression Level from 1 to 13. A lower value means a smaller size.
ParameterValue(static_cast<int>(10)),
ParameterValue(static_cast<int>(12)),
ParameterDescriptor()
.set__name("enc_mode")
.set__type(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER)
@@ -70,11 +70,11 @@ const struct ParameterDefinition kParameters[] =
#define PROP_P_FRAMES_DEFAULT 0
#define PROP_PRED_STRUCTURE_DEFAULT 2
#define PROP_GOP_SIZE_DEFAULT -1
#define PROP_INTRA_REFRESH_DEFAULT 2
#define PROP_QP_DEFAULT 50
#define PROP_INTRA_REFRESH_DEFAULT 1
#define PROP_QP_DEFAULT 35
#define PROP_DEBLOCKING_DEFAULT 1
#define PROP_RC_MODE_DEFAULT PROP_RC_MODE_CQP
#define PROP_BITRATE_DEFAULT 700000
#define PROP_BITRATE_DEFAULT 70000
#define PROP_QP_MAX_DEFAULT 63
#define PROP_QP_MIN_DEFAULT 0
#define PROP_LOOKAHEAD_DEFAULT (unsigned int)-1
@@ -268,16 +268,13 @@ void SVTAV1Publisher::publish(
EbSvtIOFormat * input_picture_buffer =
reinterpret_cast<EbSvtIOFormat *>(this->input_buf->p_buffer);

if (ycrcb_planes[0].cols == 0 && ycrcb_planes[0].rows)
{
ycrcb_planes[0] = mat_BGR2YUV_I420(cv::Rect(0, 0, cv_image.cols, cv_image.rows));
ycrcb_planes[1] = mat_BGR2YUV_I420(cv::Rect(0, cv_image.rows, cv_image.cols, cv_image.rows / 4));
ycrcb_planes[2] =
mat_BGR2YUV_I420(
cv::Rect(
0, cv_image.rows + cv_image.rows / 4, cv_image.cols,
cv_image.rows / 4));
}
ycrcb_planes[0] = mat_BGR2YUV_I420(cv::Rect(0, 0, cv_image.cols, cv_image.rows));
ycrcb_planes[1] = mat_BGR2YUV_I420(cv::Rect(0, cv_image.rows, cv_image.cols, cv_image.rows / 4));
ycrcb_planes[2] =
mat_BGR2YUV_I420(
cv::Rect(
0, cv_image.rows + cv_image.rows / 4, cv_image.cols,
cv_image.rows / 4));

input_picture_buffer->width = cv_image.cols;
input_picture_buffer->height = cv_image.rows;
@@ -353,7 +350,6 @@ void SVTAV1Publisher::publish(
memcpy(&compressed.data[message_size], output_buf->p_buffer, output_buf->n_filled_len);

svt_av1_enc_release_out_buffer(&output_buf);

publish_fn(compressed);
}
}
14 changes: 4 additions & 10 deletions svtav1_image_transport/src/svtav1_subscriber.cpp
Original file line number Diff line number Diff line change
@@ -85,7 +85,7 @@ SVTAV1Subscriber::SVTAV1Subscriber()
this->svt_decoder_config->stat_report = 0;

/* Multi-thread parameters */
this->svt_decoder_config->threads = 6;
this->svt_decoder_config->threads = 10;
this->svt_decoder_config->num_p_frames = 1;

return_error = svt_av1_dec_set_parameter(this->svt_decoder, this->svt_decoder_config);
@@ -179,8 +179,6 @@ void SVTAV1Subscriber::internalCallback(
reinterpret_cast<uint8_t *>(malloc(size >> 2));

mat_BGR2YUV_I420_decode = cv::Mat(h + h / 2, w, CV_8UC1);

std::cout << "Initialized decoder!" << std::endl;
}

output_buf->n_filled_len = msg->data.size() - (3 * sizeof(uint32_t) + sizeof(uint8_t));
@@ -219,13 +217,9 @@ void SVTAV1Subscriber::internalCallback(
if (svt_av1_dec_get_picture(this->svt_decoder, buffer, &stream_info, &frame_info) !=
EB_DecNoOutputPicture)
{
mat_BGR2YUV_I420_decode.data = reinterpret_cast<EbSvtIOFormat *>(buffer->p_buffer)->luma;

const unsigned char * cb = mat_BGR2YUV_I420_decode.data + size;
const unsigned char * cr = mat_BGR2YUV_I420_decode.data + size + (size >> 2);

cb = reinterpret_cast<EbSvtIOFormat *>(buffer->p_buffer)->cb;
cr = reinterpret_cast<EbSvtIOFormat *>(buffer->p_buffer)->cr;
memcpy(mat_BGR2YUV_I420_decode.data, ((EbSvtIOFormat *)buffer->p_buffer)->luma, size);
memcpy(&mat_BGR2YUV_I420_decode.data[w*h], ((EbSvtIOFormat *)buffer->p_buffer)->cb, (size >> 2));
memcpy(&mat_BGR2YUV_I420_decode.data[(w*h) + (size >> 2)], ((EbSvtIOFormat *)buffer->p_buffer)->cr, (size >> 2));

cv::Mat rgb;
cv::cvtColor(mat_BGR2YUV_I420_decode, rgb, cv::COLOR_YUV2RGB_I420);