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/hsv_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 HSVDecomposer::onInit()
00045 {
00046 DiagnosticNodelet::onInit();
00047 pub_h_ = advertise<sensor_msgs::Image>(*pnh_, "output/hue", 1);
00048 pub_s_ = advertise<sensor_msgs::Image>(*pnh_, "output/saturation", 1);
00049 pub_v_ = advertise<sensor_msgs::Image>(*pnh_, "output/value", 1);
00050 }
00051
00052 void HSVDecomposer::subscribe()
00053 {
00054 sub_ = pnh_->subscribe("input", 1, &HSVDecomposer::decompose, this);
00055 }
00056
00057 void HSVDecomposer::unsubscribe()
00058 {
00059 sub_.shutdown();
00060 }
00061
00062 void HSVDecomposer::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 hsv_image;
00069 std::vector<cv::Mat> hsv_planes;
00070 if (image_msg->encoding == sensor_msgs::image_encodings::BGR8) {
00071 cv::cvtColor(image, hsv_image, CV_BGR2HSV);
00072 }
00073 else if (image_msg->encoding == sensor_msgs::image_encodings::RGB8) {
00074 cv::cvtColor(image, hsv_image, CV_RGB2HSV);
00075 }
00076 else if (image_msg->encoding == sensor_msgs::image_encodings::BGRA8 ||
00077 image_msg->encoding == sensor_msgs::image_encodings::BGRA16) {
00078 cv::Mat tmp_image;
00079 cv::cvtColor(image, tmp_image, CV_BGRA2BGR);
00080 cv::cvtColor(tmp_image, hsv_image, CV_BGR2HSV);
00081 }
00082 else if (image_msg->encoding == sensor_msgs::image_encodings::RGBA8 ||
00083 image_msg->encoding == sensor_msgs::image_encodings::RGBA16) {
00084 cv::Mat tmp_image;
00085 cv::cvtColor(image, tmp_image, CV_RGBA2BGR);
00086 cv::cvtColor(tmp_image, hsv_image, CV_BGR2HSV);
00087 }
00088 else {
00089 JSK_NODELET_ERROR("unsupported format to HSV: %s", image_msg->encoding.c_str());
00090 return;
00091 }
00092 cv::split(hsv_image, hsv_planes);
00093 cv::Mat hue = hsv_planes[0];
00094 cv::Mat saturation = hsv_planes[1];
00095 cv::Mat value = hsv_planes[2];
00096 pub_h_.publish(cv_bridge::CvImage(
00097 image_msg->header,
00098 sensor_msgs::image_encodings::MONO8,
00099 hue).toImageMsg());
00100 pub_s_.publish(cv_bridge::CvImage(
00101 image_msg->header,
00102 sensor_msgs::image_encodings::MONO8,
00103 saturation).toImageMsg());
00104 pub_v_.publish(cv_bridge::CvImage(
00105 image_msg->header,
00106 sensor_msgs::image_encodings::MONO8,
00107 value).toImageMsg());
00108 }
00109 }
00110
00111 #include <pluginlib/class_list_macros.h>
00112 PLUGINLIB_EXPORT_CLASS (jsk_perception::HSVDecomposer, nodelet::Nodelet);