Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include "jsk_perception/ycc_decomposer.h"
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <opencv2/opencv.hpp>
00041
00042 namespace jsk_perception
00043 {
00044 void YCCDecomposer::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 pub_y_ = advertise<sensor_msgs::Image>(*pnh_, "output/y", 1);
00048 pub_cr_ = advertise<sensor_msgs::Image>(*pnh_, "output/cr", 1);
00049 pub_cb_ = advertise<sensor_msgs::Image>(*pnh_, "output/cb", 1);
00050 }
00051
00052 void YCCDecomposer::subscribe()
00053 {
00054 sub_ = pnh_->subscribe("input", 1, &YCCDecomposer::decompose, this);
00055 }
00056
00057 void YCCDecomposer::unsubscribe()
00058 {
00059 sub_.shutdown();
00060 }
00061
00062 void YCCDecomposer::decompose(
00063 const sensor_msgs::Image::ConstPtr& image_msg)
00064 {
00065 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00066 image_msg, image_msg->encoding);
00067 cv::Mat image = cv_ptr->image;
00068 cv::Mat ycc_image;
00069 std::vector<cv::Mat> ycc_planes;
00070 if (image_msg->encoding == sensor_msgs::image_encodings::BGR8) {
00071 cv::cvtColor(image, ycc_image, CV_BGR2YCrCb);
00072 }
00073 else if (image_msg->encoding == sensor_msgs::image_encodings::RGB8) {
00074 cv::cvtColor(image, ycc_image, CV_RGB2YCrCb);
00075 }
00076 else {
00077 JSK_NODELET_ERROR("unsupported format to YCC: %s", image_msg->encoding.c_str());
00078 return;
00079 }
00080 cv::split(ycc_image, ycc_planes);
00081 cv::Mat y = ycc_planes[0];
00082 cv::Mat cr = ycc_planes[1];
00083 cv::Mat cb = ycc_planes[2];
00084 pub_y_.publish(cv_bridge::CvImage(
00085 image_msg->header,
00086 sensor_msgs::image_encodings::MONO8,
00087 y).toImageMsg());
00088 pub_cr_.publish(cv_bridge::CvImage(
00089 image_msg->header,
00090 sensor_msgs::image_encodings::MONO8,
00091 cr).toImageMsg());
00092 pub_cb_.publish(cv_bridge::CvImage(
00093 image_msg->header,
00094 sensor_msgs::image_encodings::MONO8,
00095 cb).toImageMsg());
00096 }
00097 }
00098
00099 #include <pluginlib/class_list_macros.h>
00100 PLUGINLIB_EXPORT_CLASS (jsk_perception::YCCDecomposer, nodelet::Nodelet);