Skip to content

Commit

Permalink
Fixed image types in depth_image_proc
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
  • Loading branch information
ahcorde committed Jan 24, 2024
1 parent 0da04cb commit 994543e
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 0 deletions.
4 changes: 4 additions & 0 deletions depth_image_proc/src/point_cloud_xyzrgb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
4 changes: 4 additions & 0 deletions depth_image_proc/src/point_cloud_xyzrgb_radial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down

0 comments on commit 994543e

Please sign in to comment.