histogram.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Modified BSD License)
00003  *
00004  *  Copyright (c) 2012, PAL Robotics, S.L.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of PAL Robotics, S.L. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00038 #include <ros/ros.h>
00039 
00040 #include <pal_vision_segmentation/histogram.h>
00041 
00042 #include <boost/foreach.hpp>
00043 #include <opencv2/highgui/highgui.hpp>
00044 
00045 namespace pal_vision_util
00046 {
00047     void calcHSVHist(const cv::Mat& src, cv::MatND& histogram)
00048     {
00049         cv::Mat hsv;
00050         cv::cvtColor(src, hsv, CV_BGR2HSV);
00051         // Quantize the hue to 30 levels
00052         // and the saturation to 32 levels
00053         int hbins = 30, sbins = 32;
00054         int histSize[] = {hbins, sbins};
00055         // hue varies from 0 to 179, see cvtColor
00056         float hranges[] = { 0, 180 };
00057         // saturation varies from 0 (black-gray-white) to
00058         // 255 (pure spectrum color)
00059         float sranges[] = { 0, 256 };
00060         const float* ranges[] = { hranges, sranges };
00061 
00062         // we compute the histogram from the 0-th and 1-st channels
00063         int channels[] = {0, 1};
00064 
00065         cv::calcHist( &hsv, 1, channels, cv::Mat(), // do not use mask
00066                   histogram, 2, histSize, ranges,
00067                   true, // the histogram is uniform
00068                   false );
00069     }
00070 
00071     void calcHSVHist(const std::vector<cv::Mat>& src, std::vector<cv::MatND>& histograms)
00072     {
00073       histograms.clear();
00074 
00075       BOOST_FOREACH(const cv::Mat& mat, src)
00076       {
00077         cv::MatND hist;
00078         calcHSVHist(mat, hist);
00079         histograms.push_back(hist.clone());
00080       }
00081     }
00082 
00083     void calcHSVHist(const std::vector<cv::Mat>& src, cv::MatND& histogram)
00084     {
00085         std::vector<cv::Mat> hsv;
00086         BOOST_FOREACH(const cv::Mat& mat, src)
00087         {
00088           cv::Mat hsvMat;
00089           cv::cvtColor(mat, hsvMat, CV_BGR2HSV);
00090           hsv.push_back(hsvMat);
00091         }
00092         // Quantize the hue to 30 levels
00093         // and the saturation to 32 levels
00094         int hbins = 30, sbins = 32;
00095         int histSize[] = {hbins, sbins};
00096         // hue varies from 0 to 179, see cvtColor
00097         float hranges[] = { 0, 180 };
00098         // saturation varies from 0 (black-gray-white) to
00099         // 255 (pure spectrum color)
00100         float sranges[] = { 0, 256 };
00101         const float* ranges[] = { hranges, sranges };
00102 
00103         // we compute the histogram from the 0-th and 1-st channels
00104         int channels[] = {0, 1};
00105         cv::calcHist( hsv.data(), hsv.size(), channels, cv::Mat(), // do not use mask
00106                   histogram, 2, histSize, ranges,
00107                   true, // the histogram is uniform
00108                   false );
00109     }
00110 
00111 
00112     cv::Mat histogramImage(const cv::MatND& hist)
00113     {
00114         // Quantize the hue to 30 levels
00115         // and the saturation to 32 levels
00116         int hbins = 30, sbins = 32;
00117         double maxVal;
00118         cv::minMaxLoc(hist, 0, &maxVal, 0, 0);
00119 
00120         int scale = 10;
00121         cv::Mat histImg = cv::Mat::zeros(sbins*scale, hbins*10, CV_8UC3);
00122 
00123         for( int h = 0; h < hbins; h++ )
00124             for( int s = 0; s < sbins; s++ )
00125             {
00126             float binVal = hist.at<float>(h, s);
00127             int intensity = cvRound(binVal*255/maxVal);
00128             cv::rectangle( histImg, cv::Point(h*scale, s*scale),
00129                            cv::Point( (h+1)*scale - 1, (s+1)*scale - 1),
00130                            cv::Scalar::all(intensity),
00131                            CV_FILLED );
00132         }
00133         return histImg;
00134     }
00135 
00136     void showHist(const cv::MatND& hist, bool waitKey)
00137     {
00138         cv::Mat histImg = histogramImage(hist);
00139 
00140         cv::namedWindow( "H-S Histogram", 1 );
00141         cv::imshow( "H-S Histogram", histImg );
00142         if ( waitKey )
00143           cv::waitKey();
00144     }
00145 
00146     void backProject(const cv::Mat& image,
00147                      const cv::MatND& hist,
00148                      int threshold,
00149                      cv::Mat& result,
00150                      int dilateIterations,
00151                      int dilateSize,
00152                      int erodeIterations,
00153                      int erodeSize)
00154     {
00155       cv::Mat hsv;
00156       cv::cvtColor(image, hsv, CV_BGR2HSV);
00157       // Quantize the hue to 30 levels
00158       // and the saturation to 32 levels
00159       // hue varies from 0 to 179, see cvtColor
00160       float hranges[] = { 0, 180 };
00161       // saturation varies from 0 (black-gray-white) to
00162       // 255 (pure spectrum color)
00163       float sranges[] = { 0, 256 };
00164       const float* ranges[] = { hranges, sranges };
00165       // we compute the histogram from the 0-th and 1-st channels
00166       int channels[] = {0, 1};
00167 
00168       //back-projection takes every pixel in hsv and checks in what bin of target_hist belongs to. Then, the value of
00169       //the bin is stored in backProject in the same coordinates as the pixel
00170       cv::calcBackProject(&hsv, 1, channels, hist, result, ranges, 1, true);
00171 
00172       //normalization is not necessary as the histogram target_hist was already normalized
00173       //cv::normalize(backProject, backProject, 0, 255, cv::NORM_MINMAX, -1, cv::Mat());
00174       cv::threshold(result, result, threshold, 255, CV_THRESH_BINARY);
00175 
00176       cv::Mat tmp1, tmp2;
00177 
00178       if ( dilateIterations == 0 && erodeIterations == 0 )
00179           return;
00180 
00181       tmp1 = result;
00182 
00183       if ( dilateIterations > 0 )
00184       {
00185           cv::dilate(tmp1, erodeIterations == 0 ? result: tmp2,
00186                      cv::Mat::ones(dilateSize, dilateSize, CV_8UC1),
00187                      cv::Point(-1, -1), dilateIterations);
00188       }
00189 
00190       if ( erodeIterations > 0 )
00191       {
00192           cv::erode(dilateIterations == 0 ? tmp1 : tmp2, result,
00193                     cv::Mat::ones(erodeSize, erodeSize, CV_8UC1),
00194                     cv::Point(-1, -1), erodeIterations);
00195       }
00196 
00197     }
00198 
00199 }


pal_vision_segmentation
Author(s): Bence Magyar
autogenerated on Fri Aug 28 2015 11:57:00