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 <boost/assign.hpp>
00039 #include <jsk_topic_tools/log_utils.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <cv_bridge/cv_bridge.h>
00042 #include <opencv2/opencv.hpp>
00043
00044 namespace jsk_perception
00045 {
00046 void YCCDecomposer::onInit()
00047 {
00048 DiagnosticNodelet::onInit();
00049 pub_y_ = advertise<sensor_msgs::Image>(*pnh_, "output/y", 1);
00050 pub_cr_ = advertise<sensor_msgs::Image>(*pnh_, "output/cr", 1);
00051 pub_cb_ = advertise<sensor_msgs::Image>(*pnh_, "output/cb", 1);
00052 onInitPostProcess();
00053 }
00054
00055 void YCCDecomposer::subscribe()
00056 {
00057 sub_ = pnh_->subscribe("input", 1, &YCCDecomposer::decompose, this);
00058 ros::V_string names = boost::assign::list_of("~input");
00059 jsk_topic_tools::warnNoRemap(names);
00060 }
00061
00062 void YCCDecomposer::unsubscribe()
00063 {
00064 sub_.shutdown();
00065 }
00066
00067 void YCCDecomposer::decompose(
00068 const sensor_msgs::Image::ConstPtr& image_msg)
00069 {
00070 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00071 image_msg, image_msg->encoding);
00072 cv::Mat image = cv_ptr->image;
00073 cv::Mat ycc_image;
00074 std::vector<cv::Mat> ycc_planes;
00075 if (image_msg->encoding == sensor_msgs::image_encodings::BGR8) {
00076 cv::cvtColor(image, ycc_image, CV_BGR2YCrCb);
00077 }
00078 else if (image_msg->encoding == sensor_msgs::image_encodings::RGB8) {
00079 cv::cvtColor(image, ycc_image, CV_RGB2YCrCb);
00080 }
00081 else {
00082 NODELET_ERROR("unsupported format to YCC: %s", image_msg->encoding.c_str());
00083 return;
00084 }
00085 cv::split(ycc_image, ycc_planes);
00086 cv::Mat y = ycc_planes[0];
00087 cv::Mat cr = ycc_planes[1];
00088 cv::Mat cb = ycc_planes[2];
00089 pub_y_.publish(cv_bridge::CvImage(
00090 image_msg->header,
00091 sensor_msgs::image_encodings::MONO8,
00092 y).toImageMsg());
00093 pub_cr_.publish(cv_bridge::CvImage(
00094 image_msg->header,
00095 sensor_msgs::image_encodings::MONO8,
00096 cr).toImageMsg());
00097 pub_cb_.publish(cv_bridge::CvImage(
00098 image_msg->header,
00099 sensor_msgs::image_encodings::MONO8,
00100 cb).toImageMsg());
00101 }
00102 }
00103
00104 #include <pluginlib/class_list_macros.h>
00105 PLUGINLIB_EXPORT_CLASS (jsk_perception::YCCDecomposer, nodelet::Nodelet);