lab_color_histogram.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Georgia Institute of Technology
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 the Georgia Institute of Technology nor the names of
00018  *     its 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 
00035 #ifndef lab_color_histogram_h_DEFINED
00036 #define lab_color_histogram_h_DEFINED
00037 
00038 #include <opencv2/core/core.hpp>
00039 #include <opencv2/imgproc/imgproc.hpp>
00040 #include "abstract_feature.h"
00041 #include <iostream>
00042 
00043 namespace cpl_visual_features
00044 {
00045 template<int l_bins, int a_bins, int b_bins> class LabColorHistogram :
00046       public AbstractFeature<std::vector<float> >
00047 {
00048  public:
00049   LabColorHistogram()
00050   {
00051   }
00052 
00053   virtual void operator()(cv::Mat& patch, cv::Rect& window)
00054   {
00055     // First convert to be a 32 bit image
00056     cv::Mat cvt_patch(patch.rows, patch.cols, CV_32FC3);
00057     patch.convertTo(cvt_patch, CV_32F, 1.0/255.0);
00058 
00059     // Now convert to be in the Lab color space
00060     cv::Mat lab_patch(patch.rows, patch.cols, CV_32FC3);
00061     cv::cvtColor(cvt_patch, lab_patch, CV_BGR2Lab);
00062 
00063     int bins[] = {l_bins, a_bins, b_bins};
00064     int channels[] = {0,1,2};
00065     float l_ranges[] = {0,100};
00066     float a_ranges[] = {-128,128};
00067     float b_ranges[] = {-128,128};
00068     const float* ranges[] = {l_ranges, a_ranges, b_ranges};
00069 
00070     cv::MatND patch_desc;
00071 
00072     cv::calcHist(&lab_patch, 1, channels, cv::Mat(), patch_desc, 3,
00073                  bins, ranges, true, false);
00074 
00075     std::vector<float> desc;
00076     float color_sum = 0;
00077 
00078     for (int i = 0; i < l_bins; ++i)
00079     {
00080       for (int j = 0; j < a_bins; ++j)
00081       {
00082         for (int k = 0; k < b_bins; ++k)
00083         {
00084           desc.push_back(patch_desc.at<float>(i,j,k));
00085           color_sum += patch_desc.at<float>(i,j,k);
00086         }
00087       }
00088     }
00089 
00090 #ifdef NORMALIZE_RESULTS
00091     for (unsigned int i = 0; i < desc.size(); ++i)
00092     {
00093       desc[i] = desc[i] / color_sum;
00094     }
00095 #endif // NORMALIZE_RESULTS
00096 
00097     descriptor_ = desc;
00098   }
00099 
00100   virtual std::vector<float> getDescriptor() const
00101   {
00102     return descriptor_;
00103   }
00104 
00105  protected:
00106   std::vector<float> descriptor_;
00107 };
00108 }
00109 #endif // lab_color_histogram_h_DEFINED


cpl_visual_features
Author(s): Tucker Hermans
autogenerated on Wed Nov 27 2013 11:52:36