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

[backport humble] upport rgba8 and bgra8 encodings by skipping alpha channel (#869) #895

Merged
merged 1 commit into from
Jan 19, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
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
10 changes: 10 additions & 0 deletions depth_image_proc/src/point_cloud_xyzrgb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,11 +207,21 @@ void PointCloudXyzrgbNode::imageCb(
green_offset = 1;
blue_offset = 2;
color_step = 3;
} else if (rgb_msg->encoding == sensor_msgs::image_encodings::RGBA8) {
red_offset = 0;
green_offset = 1;
blue_offset = 2;
color_step = 4;
} else if (rgb_msg->encoding == sensor_msgs::image_encodings::BGR8) {
red_offset = 2;
green_offset = 1;
blue_offset = 0;
color_step = 3;
} else if (rgb_msg->encoding == sensor_msgs::image_encodings::BGRA8) {
red_offset = 2;
green_offset = 1;
blue_offset = 0;
color_step = 4;
} else if (rgb_msg->encoding == sensor_msgs::image_encodings::MONO8) {
red_offset = 0;
green_offset = 0;
Expand Down
10 changes: 10 additions & 0 deletions depth_image_proc/src/point_cloud_xyzrgb_radial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,11 +205,21 @@ void PointCloudXyzrgbRadialNode::imageCb(
green_offset = 1;
blue_offset = 2;
color_step = 3;
} else if (rgb_msg->encoding == sensor_msgs::image_encodings::RGBA8) {
red_offset = 0;
green_offset = 1;
blue_offset = 2;
color_step = 4;
} else if (rgb_msg->encoding == sensor_msgs::image_encodings::BGR8) {
red_offset = 2;
green_offset = 1;
blue_offset = 0;
color_step = 3;
} else if (rgb_msg->encoding == sensor_msgs::image_encodings::BGRA8) {
red_offset = 2;
green_offset = 1;
blue_offset = 0;
color_step = 4;
} else if (rgb_msg->encoding == sensor_msgs::image_encodings::MONO8) {
red_offset = 0;
green_offset = 0;
Expand Down
44 changes: 44 additions & 0 deletions stereo_image_proc/src/stereo_image_proc/stereo_processor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,6 +214,26 @@ void StereoProcessor::processPoints(
}
}
}
} else if (encoding == enc::RGBA8) {
for (int32_t u = 0; u < dense_points_.rows; ++u) {
for (int32_t v = 0; v < dense_points_.cols; ++v) {
if (isValidPoint(dense_points_(u, v))) {
const cv::Vec4b & rgb = color.at<cv::Vec4b>(u, v);
int32_t rgb_packed = (rgb[0] << 16) | (rgb[1] << 8) | rgb[2];
points.channels[0].values.push_back(*reinterpret_cast<float *>(&rgb_packed));
}
}
}
} else if (encoding == enc::BGRA8) {
for (int32_t u = 0; u < dense_points_.rows; ++u) {
for (int32_t v = 0; v < dense_points_.cols; ++v) {
if (isValidPoint(dense_points_(u, v))) {
const cv::Vec4b & bgr = color.at<cv::Vec4b>(u, v);
int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
points.channels[0].values.push_back(*reinterpret_cast<float *>(&rgb_packed));
}
}
}
} else if (encoding == enc::BGR8) {
for (int32_t u = 0; u < dense_points_.rows; ++u) {
for (int32_t v = 0; v < dense_points_.cols; ++v) {
Expand Down Expand Up @@ -317,6 +337,18 @@ void StereoProcessor::processPoints2(
}
}
}
} else if (encoding == enc::RGBA8) {
for (int32_t u = 0; u < dense_points_.rows; ++u) {
for (int32_t v = 0; v < dense_points_.cols; ++v, ++i) {
if (isValidPoint(dense_points_(u, v))) {
const cv::Vec4b & rgb = color.at<cv::Vec4b>(u, v);
int32_t rgb_packed = (rgb[0] << 16) | (rgb[1] << 8) | rgb[2];
memcpy(&points.data[i * points.point_step + 12], &rgb_packed, sizeof(int32_t));
} else {
memcpy(&points.data[i * points.point_step + 12], &bad_point, sizeof(float));
}
}
}
} else if (encoding == enc::BGR8) {
for (int32_t u = 0; u < dense_points_.rows; ++u) {
for (int32_t v = 0; v < dense_points_.cols; ++v, ++i) {
Expand All @@ -329,6 +361,18 @@ void StereoProcessor::processPoints2(
}
}
}
} else if (encoding == enc::BGRA8) {
for (int32_t u = 0; u < dense_points_.rows; ++u) {
for (int32_t v = 0; v < dense_points_.cols; ++v, ++i) {
if (isValidPoint(dense_points_(u, v))) {
const cv::Vec4b & bgr = color.at<cv::Vec4b>(u, v);
int32_t rgb_packed = (bgr[2] << 16) | (bgr[1] << 8) | bgr[0];
memcpy(&points.data[i * points.point_step + 12], &rgb_packed, sizeof(int32_t));
} else {
memcpy(&points.data[i * points.point_step + 12], &bad_point, sizeof(float));
}
}
}
} else {
RCUTILS_LOG_WARN(
"Could not fill color channel of the point cloud, unrecognized encoding '%s'",
Expand Down
Loading