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