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 <ros/ros.h>
00037 #include <nodelet/nodelet.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <cv_bridge/cv_bridge.h>
00040 #include <image_transport/image_transport.h>
00041 #include <dynamic_reconfigure/server.h>
00042 #include <boost/thread.hpp>
00043 #include <opencv/cv.h>
00044 #include <opencv/highgui.h>
00045 #include "slic.h"
00046
00047 namespace jsk_perception
00048 {
00049 class SLICSuperPixels: public nodelet::Nodelet
00050 {
00051 public:
00052 ros::NodeHandle nh_, pnh_;
00053 boost::shared_ptr<image_transport::ImageTransport> it_;
00054 boost::mutex mutex_;
00055 image_transport::Subscriber image_sub_;
00056 void imageCallback(const sensor_msgs::Image::ConstPtr& image)
00057 {
00058 boost::mutex::scoped_lock lock(mutex_);
00059 cv_bridge::CvImagePtr cv_ptr;
00060 cv_ptr = cv_bridge::toCvCopy(image, sensor_msgs::image_encodings::BGR8);
00061 cv::Mat bgr_image = cv_ptr->image;
00062
00063 IplImage bgr_image_ipl;
00064 bgr_image_ipl = bgr_image;
00065 IplImage* lab_image = cvCloneImage(&bgr_image_ipl);
00066 IplImage* out_image = cvCloneImage(&bgr_image_ipl);
00067
00068 cvCvtColor(&bgr_image_ipl, lab_image, CV_BGR2Lab);
00069 int w = image->width, h = image->height;
00070 int nr_superpixels = 200;
00071 int nc = 4;
00072 double step = sqrt((w * h) / (double) nr_superpixels);
00073 Slic slic;
00074 slic.generate_superpixels(lab_image, step, nc);
00075 slic.create_connectivity(lab_image);
00076 slic.display_contours(out_image, CV_RGB(255,0,0));
00077 cvShowImage("result", out_image);
00078 cvWaitKey(10);
00079 }
00080
00081 virtual void onInit()
00082 {
00083 nh_ = ros::NodeHandle(getNodeHandle(), "image");
00084 pnh_ = getPrivateNodeHandle();
00085 it_.reset(new image_transport::ImageTransport(nh_));
00086 image_sub_ = it_->subscribe("", 1, &SLICSuperPixels::imageCallback, this);
00087 }
00088 protected:
00089 private:
00090 };
00091 }
00092
00093 #include <pluginlib/class_list_macros.h>
00094 typedef jsk_perception::SLICSuperPixels SLICSuperPixels;
00095 PLUGINLIB_DECLARE_CLASS (jsk_perception, SLICSuperPixels, SLICSuperPixels, nodelet::Nodelet);