From 551bc00aa9deab54b2c2ec36bd73d145219bea18 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Wed, 24 Jan 2024 16:47:35 +0100 Subject: [PATCH] [backport humble] Fixed image types in depth_image_proc (#916) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit backport humble https://github.com/ros-perception/image_pipeline/pull/915#event-11585393591 Signed-off-by: Alejandro Hernández Cordero --- depth_image_proc/src/point_cloud_xyzrgb.cpp | 4 ++++ depth_image_proc/src/point_cloud_xyzrgb_radial.cpp | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/depth_image_proc/src/point_cloud_xyzrgb.cpp b/depth_image_proc/src/point_cloud_xyzrgb.cpp index f5d3c0380..2f3daec81 100644 --- a/depth_image_proc/src/point_cloud_xyzrgb.cpp +++ b/depth_image_proc/src/point_cloud_xyzrgb.cpp @@ -267,6 +267,10 @@ void PointCloudXyzrgbNode::imageCb( convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); } else if (rgb_msg->encoding == sensor_msgs::image_encodings::BGR8) { convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); + } else if (rgb_msg->encoding == sensor_msgs::image_encodings::BGRA8) { + convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); + } else if (rgb_msg->encoding == sensor_msgs::image_encodings::RGBA8) { + convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); } else if (rgb_msg->encoding == sensor_msgs::image_encodings::MONO8) { convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); } else { diff --git a/depth_image_proc/src/point_cloud_xyzrgb_radial.cpp b/depth_image_proc/src/point_cloud_xyzrgb_radial.cpp index 55e0e23d3..ec76889c8 100644 --- a/depth_image_proc/src/point_cloud_xyzrgb_radial.cpp +++ b/depth_image_proc/src/point_cloud_xyzrgb_radial.cpp @@ -265,6 +265,10 @@ void PointCloudXyzrgbRadialNode::imageCb( convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); } else if (rgb_msg->encoding == sensor_msgs::image_encodings::BGR8) { convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); + } else if (rgb_msg->encoding == sensor_msgs::image_encodings::BGRA8) { + convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); + } else if (rgb_msg->encoding == sensor_msgs::image_encodings::RGBA8) { + convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); } else if (rgb_msg->encoding == sensor_msgs::image_encodings::MONO8) { convertRgb(rgb_msg, cloud_msg, red_offset, green_offset, blue_offset, color_step); } else {