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/rgb_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 RGBDecomposer::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 pub_r_ = advertise<sensor_msgs::Image>(*pnh_, "output/red", 1);
00048 pub_g_ = advertise<sensor_msgs::Image>(*pnh_, "output/green", 1);
00049 pub_b_ = advertise<sensor_msgs::Image>(*pnh_, "output/blue", 1);
00050 }
00051
00052 void RGBDecomposer::subscribe()
00053 {
00054 sub_ = pnh_->subscribe("input", 1, &RGBDecomposer::decompose, this);
00055 }
00056
00057 void RGBDecomposer::unsubscribe()
00058 {
00059 sub_.shutdown();
00060 }
00061
00062 void RGBDecomposer::decompose(
00063 const sensor_msgs::Image::ConstPtr& image_msg)
00064 {
00065 if ((image_msg->width == 0) && (image_msg->height == 0)) {
00066 JSK_ROS_WARN("invalid image input");
00067 return;
00068 }
00069 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00070 image_msg, image_msg->encoding);
00071 cv::Mat image = cv_ptr->image;
00072 if (image_msg->encoding == sensor_msgs::image_encodings::RGB8) {
00073 cv::cvtColor(image, image, CV_RGB2BGR);
00074 }
00075 std::vector<cv::Mat> bgr_planes;
00076 cv::split(image, bgr_planes);
00077 cv::Mat red = bgr_planes[2];
00078 cv::Mat blue = bgr_planes[0];
00079 cv::Mat green = bgr_planes[1];
00080 pub_r_.publish(cv_bridge::CvImage(
00081 image_msg->header,
00082 sensor_msgs::image_encodings::MONO8,
00083 red).toImageMsg());
00084 pub_g_.publish(cv_bridge::CvImage(
00085 image_msg->header,
00086 sensor_msgs::image_encodings::MONO8,
00087 green).toImageMsg());
00088 pub_b_.publish(cv_bridge::CvImage(
00089 image_msg->header,
00090 sensor_msgs::image_encodings::MONO8,
00091 blue).toImageMsg());
00092 }
00093 }
00094
00095 #include <pluginlib/class_list_macros.h>
00096 PLUGINLIB_EXPORT_CLASS (jsk_perception::RGBDecomposer, nodelet::Nodelet);