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