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 #include "jsk_perception/slic_superpixels.h"
00037 #include "slic.h"
00038 #include <sensor_msgs/image_encodings.h>
00039
00040 namespace jsk_perception
00041 {
00042
00043 void SLICSuperPixels::onInit()
00044 {
00045 nh_ = ros::NodeHandle(getNodeHandle(), "image");
00046 pnh_ = getPrivateNodeHandle();
00047 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (pnh_);
00048 dynamic_reconfigure::Server<Config>::CallbackType f =
00049 boost::bind (
00050 &SLICSuperPixels::configCallback, this, _1, _2);
00051 srv_->setCallback (f);
00052
00053 it_.reset(new image_transport::ImageTransport(nh_));
00054 pub_ = pnh_.advertise<sensor_msgs::Image>("output", 1);
00055 pub_debug_ = pnh_.advertise<sensor_msgs::Image>("debug", 1);
00056 pub_debug_mean_color_ = pnh_.advertise<sensor_msgs::Image>("debug/mean_color", 1);
00057 pub_debug_center_grid_ = pnh_.advertise<sensor_msgs::Image>("debug/center_grid", 1);
00058 image_sub_ = it_->subscribe("", 1, &SLICSuperPixels::imageCallback, this);
00059 }
00060
00061 void SLICSuperPixels::imageCallback(const sensor_msgs::Image::ConstPtr& image)
00062 {
00063 boost::mutex::scoped_lock lock(mutex_);
00064 cv::Mat in_image = cv_bridge::toCvShare(image, image->encoding)->image;
00065 cv::Mat bgr_image;
00066 if (in_image.channels() == 1) {
00067
00068 cv::cvtColor(in_image, bgr_image, CV_GRAY2BGR);
00069 }
00070 else if (image->encoding == sensor_msgs::image_encodings::RGB8) {
00071
00072 cv::cvtColor(in_image, bgr_image, CV_RGB2BGR);
00073 }
00074 else {
00075 bgr_image = in_image;
00076 }
00077
00078 cv::Mat lab_image, out_image, mean_color_image, center_grid_image;
00079
00080 bgr_image.copyTo(out_image);
00081 bgr_image.copyTo(mean_color_image);
00082 bgr_image.copyTo(center_grid_image);
00083 cv::cvtColor(bgr_image, lab_image, CV_BGR2Lab);
00084 int w = image->width, h = image->height;
00085 double step = sqrt((w * h) / (double) number_of_super_pixels_);
00086 Slic slic;
00087 slic.generate_superpixels(lab_image, step, weight_);
00088 slic.create_connectivity(lab_image);
00089 slic.colour_with_cluster_means(mean_color_image);
00090 slic.display_center_grid(center_grid_image, cv::Scalar(0, 0, 255));
00091 slic.display_contours(out_image, cv::Vec3b(0,0,255));
00092 pub_debug_.publish(cv_bridge::CvImage(
00093 image->header,
00094 sensor_msgs::image_encodings::BGR8,
00095 out_image).toImageMsg());
00096 pub_debug_mean_color_.publish(cv_bridge::CvImage(
00097 image->header,
00098 sensor_msgs::image_encodings::BGR8,
00099 mean_color_image).toImageMsg());
00100 pub_debug_center_grid_.publish(cv_bridge::CvImage(
00101 image->header,
00102 sensor_msgs::image_encodings::BGR8,
00103 center_grid_image).toImageMsg());
00104
00105 cv::Mat clusters;
00106 cv::transpose(slic.clusters, clusters);
00107 clusters = clusters + cv::Scalar(1);
00108 pub_.publish(cv_bridge::CvImage(
00109 image->header,
00110 sensor_msgs::image_encodings::TYPE_32SC1,
00111 clusters).toImageMsg());
00112 }
00113
00114 void SLICSuperPixels::configCallback(Config &config, uint32_t level)
00115 {
00116 boost::mutex::scoped_lock lock(mutex_);
00117 weight_ = config.weight;
00118 number_of_super_pixels_ = config.number_of_super_pixels;
00119 }
00120 }
00121
00122 #include <pluginlib/class_list_macros.h>
00123 PLUGINLIB_EXPORT_CLASS (jsk_perception::SLICSuperPixels, nodelet::Nodelet);