Skip to content

Commit

Permalink
added supported for visualizing yuv422
Browse files Browse the repository at this point in the history
Signed-off-by: Joshua Kurien <jkurien@blackberry.com>
  • Loading branch information
joshua-qnx committed Apr 15, 2021
1 parent b0c1389 commit b264e72
Showing 1 changed file with 6 additions and 1 deletion.
7 changes: 6 additions & 1 deletion image_tools/src/showimage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,6 +180,8 @@ class ShowImage : public rclcpp::Node
return CV_32FC1;
} else if (encoding == "rgb8") {
return CV_8UC3;
} else if (encoding == "yuv422") {
return CV_8UC2;
} else {
throw std::runtime_error("Unsupported encoding type");
}
Expand All @@ -202,7 +204,10 @@ class ShowImage : public rclcpp::Node

if (msg->encoding == "rgb8") {
cv::cvtColor(frame, frame, cv::COLOR_RGB2BGR);
}
} else if (msg->encoding == "yuv422") {
msg->is_bigendian? cv::cvtColor(frame, frame, cv::COLOR_YUV2BGR_UYVY):
cv::cvtColor(frame, frame, cv::COLOR_YUV2BGR_YUYV);
}

cv::Mat cvframe = frame;

Expand Down

0 comments on commit b264e72

Please sign in to comment.