Skip to content

Commit

Permalink
support rgba8 and bgra8 encodings by skipping alpha channel
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde committed Jan 19, 2024
1 parent 5645baa commit 4c27717
Showing 1 changed file with 10 additions and 0 deletions.
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 @@ -195,11 +195,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

0 comments on commit 4c27717

Please sign in to comment.