slic.cpp
Go to the documentation of this file.
00001 #include "slic.h"
00002 
00003 
00004 /*
00005  * Constructor. Nothing is done here.
00006  */
00007 Slic::Slic() {
00008 
00009 }
00010 
00011 /*
00012  * Destructor. Clear any present data.
00013  */
00014 Slic::~Slic() {
00015 }
00016 
00017 /*
00018  * Clear the data as saved by the algorithm.
00019  *
00020  * Input : -
00021  * Output: -
00022  */
00023 void Slic::clear_data() {
00024     clusters.release();
00025     distances.release();
00026     centers.release();
00027     center_counts.clear();
00028 }
00029 
00030 /*
00031  * Initialize the cluster centers and initial values of the pixel-wise cluster
00032  * assignment and distance values.
00033  *
00034  * Input : The image (cv::Mat).
00035  * Output: -
00036  */
00037 void Slic::init_data(const cv::Mat &image) {
00038     /* Initialize the cluster and distance matrices. */
00039 
00040     clusters  = cv::Mat_<int>(image.cols,image.rows,-1);
00041     distances = cv::Mat_<double>(image.cols,image.rows,DBL_MAX);
00042 
00043     /* Initialize the centers and counters. */
00044     for (int i = step; i < image.cols - step/2; i += step) {
00045         for (int j = step; j < image.rows - step/2; j += step) {
00046             /* Find the local minimum (gradient-wise). */
00047             cv::Point nc = find_local_minimum(image, cv::Point(i,j));
00048             cv::Vec3b colour = image.at<cv::Vec3b>(nc.y, nc.x);
00049             
00050             /* Generate the center vector. */
00051             Vec5d center(colour[0], colour[1], colour[2], nc.x, nc.y);
00052             
00053             /* Append to vector of centers. */
00054             centers.push_back(center);
00055             center_counts.push_back(0);
00056         }
00057     }
00058 }
00059 
00060 /*
00061  * Compute the distance between a cluster center and an individual pixel.
00062  *
00063  * Input : The cluster index (int), the pixel (cv::Point), and the Lab values of
00064  *         the pixel (cv::Scalar).
00065  * Output: The distance (double).
00066  */
00067 double Slic::compute_dist(int ci, cv::Point pixel, cv::Vec3b colour) {
00068     Vec5d cen(centers(ci));
00069     double dc = sqrt(pow(cen[0] - colour[0], 2) + pow(cen[1]
00070             - colour[1], 2) + pow(cen[2] - colour[2], 2));
00071     double ds = sqrt(pow(cen[3] - pixel.x, 2) + pow(cen[4] - pixel.y, 2));
00072     
00073     return sqrt(pow(dc / nc, 2) + pow(ds / ns, 2));
00074     
00075     //double w = 1.0 / (pow(ns / nc, 2));
00076     //return sqrt(dc) + sqrt(ds * w);
00077 }
00078 
00079 /*
00080  * Find a local gradient minimum of a pixel in a 3x3 neighbourhood. This
00081  * method is called upon initialization of the cluster centers.
00082  *
00083  * Input : The image (cv::Mat &) and the pixel center (cv::Point).
00084  * Output: The local gradient minimum (cv::Point).
00085  */
00086 cv::Point Slic::find_local_minimum(const cv::Mat_<cv::Vec3b> &image, cv::Point center) {
00087     double min_grad = DBL_MAX;
00088     cv::Point loc_min(center.x, center.y);
00089     
00090     for (int i = center.x-1; i < center.x+2; i++) {
00091         for (int j = center.y-1; j < center.y+2; j++) {
00092             cv::Vec3b c1 = image(j+1, i);
00093             cv::Vec3b c2 = image(j, i+1);
00094             cv::Vec3b c3 = image(j, i);
00095             /* Convert colour values to grayscale values. */
00096             double i1 = c1[0];
00097             double i2 = c2[0];
00098             double i3 = c3[0];
00099             /*double i1 = c1.val[0] * 0.11 + c1.val[1] * 0.59 + c1.val[2] * 0.3;
00100             double i2 = c2.val[0] * 0.11 + c2.val[1] * 0.59 + c2.val[2] * 0.3;
00101             double i3 = c3.val[0] * 0.11 + c3.val[1] * 0.59 + c3.val[2] * 0.3;*/
00102             
00103             /* Compute horizontal and vertical gradients and keep track of the
00104                minimum. */
00105             if (sqrt(pow(i1 - i3, 2)) + sqrt(pow(i2 - i3,2)) < min_grad) {
00106                 min_grad = fabs(i1 - i3) + fabs(i2 - i3);
00107                 loc_min.x = i;
00108                 loc_min.y = j;
00109             }
00110         }
00111     }
00112     
00113     return loc_min;
00114 }
00115 
00116 /*
00117  * Compute the over-segmentation based on the step-size and relative weighting
00118  * of the pixel and colour values.
00119  *
00120  * Input : The Lab image (cv::Mat), the stepsize (int), and the weight (int).
00121  * Output: -
00122  */
00123 void Slic::generate_superpixels(const cv::Mat &img, int step, int nc) {
00124     this->step = step;
00125     this->nc = nc;
00126     this->ns = step;
00127 
00128     /* make a new Mat header, that allows us to iterate the image more efficiently. */
00129     cv::Mat_<cv::Vec3b> image(img);
00130 
00131     /* Clear previous data (if any), and re-initialize it. */
00132     clear_data();
00133     init_data(image);
00134     
00135     /* Run EM for 10 iterations (as prescribed by the algorithm). */
00136     for (int i = 0; i < NR_ITERATIONS; i++) {
00137         /* Reset distance values. */
00138         distances = FLT_MAX;
00139 
00140         for (int j = 0; j < centers.rows; j++) {
00141             Vec5d cen(centers(j));
00142             /* Only compare to pixels in a 2 x step by 2 x step region. */
00143             for (int k = int(cen[3]) - step; k < int(cen[3]) + step; k++) {
00144                 for (int l = int(cen[4]) - step; l < int(cen[4]) + step; l++) {
00145                 
00146                     if (k >= 0 && k < image.cols && l >= 0 && l < image.rows) {
00147                         cv::Vec3b colour = image(l, k);
00148                         double d = compute_dist(j, cv::Point(k,l), colour);
00149                         
00150                         /* Update cluster allocation if the cluster minimizes the
00151                            distance. */
00152                         if (d < distances(k,l)) {
00153                             distances(k,l) = d;
00154                             clusters(k,l) = j;
00155                         }
00156                     }
00157                 }
00158             }
00159         }
00160         
00161         /* Clear the center values. */
00162         for (int j = 0; j < centers.rows; j++) {
00163             centers(j) = 0;
00164             center_counts[j] = 0;
00165         }
00166         
00167         /* Compute the new cluster centers. */
00168         for (int j = 0; j < image.cols; j++) {
00169             for (int k = 0; k < image.rows; k++) {
00170                 int c_id = clusters(j,k);
00171                 
00172                 if (c_id != -1) {
00173                     cv::Vec3b colour = image(k, j);                    
00174                     centers(c_id) += Vec5d(colour[0], colour[1], colour[2], j, k);                    
00175                     center_counts[c_id] += 1;
00176                 }
00177             }
00178         }
00179 
00180         /* Normalize the clusters. */
00181         for (int j = 0; j < centers.rows; j++) {
00182             centers(j) /= center_counts[j];
00183         }
00184     }
00185 }
00186 
00187 /*
00188  * Enforce connectivity of the superpixels. This part is not actively discussed
00189  * in the paper, but forms an active part of the implementation of the authors
00190  * of the paper.
00191  *
00192  * Input : The image (cv::Mat).
00193  * Output: -
00194  */
00195 void Slic::create_connectivity(const cv::Mat &image) {
00196     int label = 0, adjlabel = 0;
00197     const int lims = (image.cols * image.rows) / (centers.rows);
00198     
00199     const int dx4[4] = {-1,  0,  1,  0};
00200         const int dy4[4] = { 0, -1,  0,  1};
00201     
00202     /* Initialize the new cluster matrix. */
00203     cv::Mat_<int> new_clusters(image.cols,image.rows,-1);
00204 
00205     for (int i = 0; i < image.cols; i++) {
00206         for (int j = 0; j < image.rows; j++) {
00207             if (new_clusters(i,j) == -1) {
00208                 vector<cv::Point> elements;
00209                 elements.push_back(cv::Point(i, j));
00210             
00211                 /* Find an adjacent label, for possible use later. */
00212                 for (int k = 0; k < 4; k++) {
00213                     int x = elements[0].x + dx4[k], y = elements[0].y + dy4[k];
00214                     
00215                     if (x >= 0 && x < image.cols && y >= 0 && y < image.rows) {
00216                         if (new_clusters(x,y) >= 0) {
00217                             adjlabel = new_clusters(x,y);
00218                         }
00219                     }
00220                 }
00221                 
00222                 int count = 1;
00223                 for (int c = 0; c < count; c++) {
00224                     for (int k = 0; k < 4; k++) {
00225                         int x = elements[c].x + dx4[k], y = elements[c].y + dy4[k];
00226                         
00227                         if (x >= 0 && x < image.cols && y >= 0 && y < image.rows) {
00228                             if (new_clusters(x,y) == -1 && clusters(i,j) == clusters(x,y)) {
00229                                 elements.push_back(cv::Point(x, y));
00230                                 new_clusters(x,y) = label;
00231                                 count += 1;
00232                             }
00233                         }
00234                     }
00235                 }
00236                 
00237                 /* Use the earlier found adjacent label if a segment size is
00238                    smaller than a limit. */
00239                 if (count <= lims >> 2) {
00240                     for (int c = 0; c < count; c++) {
00241                         new_clusters(elements[c].x, elements[c].y) = adjlabel;
00242                     }
00243                     label -= 1;
00244                 }
00245                 label += 1;
00246             }
00247         }
00248     }
00249     //clusters = new_clusters;
00250 }
00251 
00252 /*
00253  * Display the cluster centers.
00254  *
00255  * Input : The image to display upon (cv::Mat) and the colour (cv::Vec3b).
00256  * Output: -
00257  */
00258 void Slic::display_center_grid(cv::Mat &image, cv::Scalar colour) {
00259     for (int i = 0; i < centers.rows; i++) {
00260         cv::circle(image, cv::Point2d(centers(i)[3], centers(i)[4]), 2, colour, 2);
00261     }
00262 }
00263 
00264 /*
00265  * Display a single pixel wide contour around the clusters.
00266  *
00267  * Input : The target image (cv::Mat) and contour colour (cv::Vec3b).
00268  * Output: -
00269  */
00270 void Slic::display_contours(cv::Mat &image, cv::Vec3b colour) {
00271     const int dx8[8] = {-1, -1,  0,  1, 1, 1, 0, -1};
00272         const int dy8[8] = { 0, -1, -1, -1, 0, 1, 1,  1};
00273         
00274         /* Initialize the contour vector and the matrix detailing whether a pixel
00275          * is already taken to be a contour. */
00276         vector<cv::Point> contours;
00277     cv::Mat_<uchar> istaken(image.cols, image.rows, uchar(0));
00278     
00279     /* Go through all the pixels. */
00280     for (int i = 0; i < image.cols; i++) {
00281         for (int j = 0; j < image.rows; j++) {
00282             int nr_p = 0;
00283             
00284             /* Compare the pixel to its 8 neighbours. */
00285             for (int k = 0; k < 8; k++) {
00286                 int x = i + dx8[k], y = j + dy8[k];
00287                 
00288                 if (x >= 0 && x < image.cols && y >= 0 && y < image.rows) {
00289                     if (istaken(x,y) == false && clusters(i,j) != clusters(x,y)) {
00290                         nr_p += 1;
00291                     }
00292                 }
00293             }
00294             
00295             /* Add the pixel to the contour list if desired. */
00296             if (nr_p >= 2) {
00297                 contours.push_back(cv::Point(i,j));
00298                 istaken(i,j) = true;
00299             }
00300         }
00301     }
00302     
00303     /* Draw the contour pixels. */
00304     for (int i = 0; i < (int)contours.size(); i++) {
00305         image.at<cv::Vec3b>(contours[i].y, contours[i].x) = colour;
00306     }
00307 }
00308 
00309 /*
00310  * Give the pixels of each cluster the same colour values. The specified colour
00311  * is the mean RGB colour per cluster.
00312  *
00313  * Input : The target image (cv::Mat).
00314  * Output: -
00315  */
00316 void Slic::colour_with_cluster_means(cv::Mat &image) {
00317     vector<cv::Vec3i> colours(centers.rows);
00318     /* fill */
00319     for (size_t i = 0; i < colours.size(); i++) {
00320       colours[i] = cv::Vec3i(0, 0, 0);
00321     }
00322     /* Gather the colour values per cluster. */
00323     for (int i = 0; i < image.cols; i++) {
00324         for (int j = 0; j < image.rows; j++) {
00325             int index = clusters(i,j);
00326             cv::Vec3b c = image.at<cv::Vec3b>(j, i);
00327             colours[index][0] += (c[0]);
00328             colours[index][1] += (c[1]);
00329             colours[index][2] += (c[2]);
00330         }
00331     }
00332     
00333     /* Divide by the number of pixels per cluster to get the mean colour. */
00334     for (int i = 0; i < (int)colours.size(); i++) {
00335         colours[i] /= center_counts[i];
00336     }
00337     
00338     /* Fill in. */
00339     for (int i = 0; i < image.cols; i++) {
00340         for (int j = 0; j < image.rows; j++) {
00341             cv::Vec3i c = colours[clusters(i,j)];
00342             image.at<cv::Vec3b>(j, i) = cv::Vec3b(c[0], c[1], c[2]);
00343         }
00344     }
00345 }


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07