Histogram.h
Go to the documentation of this file.
00001 /* Copyright (C) 2012 Christian Lutz, Thorsten Engesser
00002  * 
00003  * This file is part of motld
00004  * 
00005  * This program is free software: you can redistribute it and/or modify
00006  * it under the terms of the GNU General Public License as published by
00007  * the Free Software Foundation, either version 3 of the License, or
00008  * (at your option) any later version.
00009  * 
00010  * This program is distributed in the hope that it will be useful,
00011  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00012  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013  * GNU General Public License for more details.
00014  * 
00015  * You should have received a copy of the GNU General Public License
00016  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
00017  */
00018 
00019 #ifndef HISTOGRAM_H
00020 #define HISTOGRAM_H
00021 
00022 #include <cmath>
00023 #include <cstring>
00024 #include <vector>
00025 #include "Matrix.h"
00026 
00027 #define MAX3(a,b,c) a > b ? (a > c ? a : c) : (b > c ? b : c);
00028 #define MIN3(a,b,c) a < b ? (a < c ? a : c) : (b < c ? b : c);
00029 
00030 #define NUM_BINS 7
00031 #define GRAY_THRESHOLD 0.125
00032 
00033 namespace motld {
00035   class Histogram {
00036   public:
00038     static Histogram * getInstance();
00040     float * getColorDistribution(const unsigned char * const rgb, const int & size) const;
00042     float * getColorDistribution(const unsigned char * const rgb, const int & width, const int & height) const;
00044     float * getColorDistribution(const unsigned char * const rgb, const int & width, const int & height, const ObjectBox & box) const;
00046     unsigned char * debugImage(const int & bin, int & sideLength) const;
00048     static float compareColorDistribution(const float * const hist1, const float * const hist2);
00049   
00050   private:
00051     Histogram();
00052     ~Histogram();
00053   
00054     static void toHS(const float & r, const float & g, const float & b, float & h, float & s);
00055     static float chiSquareSym(const float * const distr1, const float * const distr2, const int & n);
00056     static float chiSquare(const float * const correctHistogram, const float * const toCheck, const int & n);
00057   
00058     static Histogram * ivInstance;
00059     unsigned char * ivLookupRGB;
00060   };
00061 
00062   Histogram * Histogram::ivInstance = NULL;
00063 
00064   Histogram * Histogram::getInstance()
00065   {
00066     if (ivInstance == NULL)
00067     {
00068       ivInstance = new Histogram();
00069     }
00070     return ivInstance;
00071   }
00072 
00073   Histogram::Histogram()
00074   {
00075     ivLookupRGB = new unsigned char[4096];
00076   
00077     int numColors = 2*(NUM_BINS - 1);
00078     float colorSize  = 360 / numColors;
00079     float colorStart = 0.5 * colorSize;
00080   
00081 #pragma omp parallel for
00082     for (int c = 0; c < 4096; ++c)
00083     {
00084       // determine color voxel
00085       unsigned char red   = (c >> 8) & 15;
00086       unsigned char green = (c >> 4) & 15;
00087       unsigned char blue  =  c       & 15;
00088     
00089       // calculate r/g/b value in center of color voxel
00090       float r = (red   + 0.5) / 16.;
00091       float g = (green + 0.5) / 16.;
00092       float b = (blue  + 0.5) / 16.;
00093     
00094       // calculate hue and grayness value
00095       float h = 0.f, s = 0.f;
00096       toHS(r, g, b, h, s);
00097     
00098       if (s < GRAY_THRESHOLD)
00099       {
00100         ivLookupRGB[c] = 0;
00101       }
00102       else
00103       {
00104         int bin = 1 + (int)((h + colorStart) / colorSize) % numColors;
00105         ivLookupRGB[c] = bin;
00106       }
00107     }  
00108   }
00109 
00110   Histogram::~Histogram()
00111   {
00112     delete [] ivLookupRGB;
00113     delete ivInstance;
00114   }
00115 
00116   float * Histogram::getColorDistribution(const unsigned char * const rgb, const int & size) const
00117   {
00118     float * result = new float[NUM_BINS]; memset(result, 0., NUM_BINS * sizeof(float));
00119   
00120     int numPrebins = 2 * NUM_BINS - 1;
00121     float * prebinning = new float[numPrebins]; memset(prebinning, 0., numPrebins * sizeof(float));
00122   
00123     const unsigned char * red = rgb;
00124     const unsigned char * green = red + size;
00125     const unsigned char * blue = green + size;
00126   
00127     for (int p = 0; p < size; ++p)
00128     {
00129       int r = red[p] >> 4, g = green[p] >> 4, b = blue[p] >> 4;
00130       int c = (((r<<4)|g)<<4)|b;
00131       prebinning[ivLookupRGB[c]] += 1;
00132     }
00133   
00134     for (int i = 0; i < numPrebins; ++i)
00135     {
00136       prebinning[i] /= size;
00137     }
00138   
00139     // 0  1  2  3  4  5  6  7  8  9 10 11 12
00140     //    1     2     3     4     5     6
00141   
00142     result[0] = prebinning[0];
00143     prebinning[0] = prebinning[12];
00144     for (int i = 1; i < NUM_BINS; ++i)
00145     {
00146       result[i] = 0.5 * prebinning[2*i-2] + prebinning[2*i-1] + 0.5 * prebinning[2*i];
00147     }
00148   
00149     delete[] prebinning;
00150     return result;
00151   }
00152 
00153   float * Histogram::getColorDistribution(const unsigned char * const rgb, const int & width, const int & height) const
00154   {
00155     return getColorDistribution(rgb, width * height);
00156   }
00157 
00158   float * Histogram::getColorDistribution(const unsigned char * const rgb, const int & width,
00159                                           const int & height, const ObjectBox & box) const
00160   {
00161     float * result = new float[NUM_BINS]; memset(result, 0., NUM_BINS * sizeof(float));
00162   
00163     int numPrebins = 2 * NUM_BINS - 1;
00164     float * prebinning = new float[numPrebins]; memset(prebinning, 0., numPrebins * sizeof(float));
00165   
00166     int size = width * height;
00167     const unsigned char* red = rgb;
00168     const unsigned char* green = red + size;
00169     const unsigned char* blue = green + size;
00170   
00171     int bw = box.width-2, bh = box.height-2;
00172     int npixels = 0;
00173     for (int dx = 2; dx < bw; ++dx)
00174     {
00175       for (int dy = 2; dy < bh; ++dy)
00176       {
00177         int x = round(box.x) + dx, y = round(box.y) + dy;
00178         if(x < 0 || y < 0)
00179           continue;
00180         if(x >= width || y >= height)
00181           break;
00182         int p = y * width + x;
00183         int r = red[p] >> 4, g = green[p] >> 4, b = blue[p] >> 4;
00184         int c = (((r<<4)|g)<<4)|b;
00185         prebinning[ivLookupRGB[c]] += 1;
00186         npixels++;
00187       }
00188     }
00189   
00190     float invBoxSize = 1.0/npixels;
00191     for (int i = 0; i < numPrebins; ++i)
00192     {
00193       prebinning[i] *= invBoxSize;
00194     }
00195   
00196     result[0] = prebinning[0];
00197     prebinning[0] = prebinning[12];
00198     for (int i = 1; i < NUM_BINS; ++i)
00199     {
00200       result[i] = 0.5 * prebinning[2*i-2] + prebinning[2*i-1] + 0.5 * prebinning[2*i];
00201     }
00202   
00203     delete[] prebinning;
00204     return result;
00205   }
00206 
00207   float Histogram::compareColorDistribution(const float * const correctHistogram, const float * const candidateHistogram)
00208   {
00209     return 1 - chiSquareSym(correctHistogram, candidateHistogram, NUM_BINS);
00210   }
00211 
00212   unsigned char * Histogram::debugImage(const int & bin, int & sideLength) const
00213   {
00214     std::vector<unsigned char> rs;
00215     std::vector<unsigned char> gs;
00216     std::vector<unsigned char> bs;
00217   
00218     for (int c = 0; c < 4096; ++c)
00219     {
00220       if (ivLookupRGB[c] == bin)
00221       {
00222         // determine color voxel
00223         unsigned char r = (c >> 8) & 15;
00224         unsigned char g = (c >> 4) & 15;
00225         unsigned char b =  c       & 15;
00226       
00227         rs.push_back(r * 16 + 0.5);
00228         gs.push_back(g * 16 + 0.5);
00229         bs.push_back(b * 16 + 0.5);
00230       }
00231     }
00232   
00233     int sqsize = ceil(sqrt((float)rs.size()));
00234     sideLength = sqsize*12;
00235   
00236     unsigned char * result = new unsigned char[3*12*12*sqsize*sqsize];
00237     memset(result,0,3*12*12*sqsize*sqsize*sizeof(unsigned char));
00238     unsigned char * red   = result;
00239     unsigned char * green = red   + 12*12*sqsize*sqsize;
00240     unsigned char * blue  = green + 12*12*sqsize*sqsize;
00241   
00242     for (unsigned int i = 0; i < rs.size(); ++i)
00243     {
00244       unsigned int row = i / sqsize;
00245       unsigned int col = i % sqsize;
00246     
00247       for (unsigned int y = row * 12 + 1; y < row * 12 + 11; ++y)
00248       {
00249         for (unsigned int x = col * 12 + 1; x < col * 12 +11; ++x)
00250         {
00251           red  [12 * sqsize * y + x] = rs[i];
00252           green[12 * sqsize * y + x] = gs[i];
00253           blue [12 * sqsize * y + x] = bs[i];
00254         }
00255       }
00256     }
00257     return result;
00258   }
00259 
00260   void Histogram::toHS(const float & r, const float & g, const float & b, float & h, float & s)
00261   {
00262     float max = MAX3(r,g,b);
00263     float min = MIN3(r,g,b);
00264     float dmm = max - min;
00265   
00266     if      (dmm == 0) h = 0; 
00267     else if (max == r) h = 60 * (0 + (g-b)/dmm);
00268     else if (max == g) h = 60 * (2 + (b-r)/dmm);
00269     else if (max == b) h = 60 * (4 + (r-g)/dmm);
00270     h = h < 0 ? h + 360 : h;
00271   
00272     if (max == 0) s = 0;
00273     else          s = dmm / max;
00274   }
00275 
00276   inline float Histogram::chiSquareSym(const float * const v1, const float * const v2, const int & n)
00277   {
00278     float chisqr2 = 0.;
00279     for (int j = 0; j < n; ++j)
00280     {
00281       float diff = v1[j] - v2[j];
00282       float sum  = v1[j] + v2[j];
00283       chisqr2 += sum == 0 ? 0 : diff * diff / sum;
00284     }
00285     return 0.5 * chisqr2;
00286   }
00287 
00288   float Histogram::chiSquare(const float*const correctHistogram, const float*const toCheck, const int& n)
00289   {
00290     float chisqr = 0.;
00291     for (int j = 0; j < n; ++j)
00292     {
00293       float correct = correctHistogram[j];
00294       float diff = toCheck[j] - correct;
00295       chisqr += correct > 0.0001 ? diff * diff / correct : 0;
00296     }
00297     return chisqr;
00298   
00299   }
00300 }
00301 
00302 #endif // HISTOGRAM_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


motld
Author(s): Jost Tobias Springenberg, Jan Wuelfing
autogenerated on Wed Dec 26 2012 16:24:49