attribute_learning_base_feature.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 attribute_learning_base_feature_h_DEFINED
00036 #define attribute_learning_base_feature_h_DEFINED
00037 
00038 #include <opencv2/core/core.hpp>
00039 #include <opencv2/imgproc/imgproc.hpp>
00040 #include "abstract_feature.h"
00041 #include "lab_color_histogram.h"
00042 #include "lm_filter_bank.h"
00043 #include "canny_edges.h"
00044 #include "my_hog.h"
00045 #include "sift_des.h"
00046 #include <string>
00047 #include <vector>
00048 
00049 //#define USE_CANNY_DESC 1
00050 #define USE_LAB_DESC 1
00051 #define USE_TEXT_DESC 1
00052 //#define USE_HOG_DESC 1
00053 #define USE_SIFT_DESC 1
00054 //#define NORMALIZE_VALUES 1
00055 
00056 namespace cpl_visual_features
00057 {
00058 class AttributeLearningBaseFeature : public AbstractFeature<std::vector<float> >
00059 {
00060  public:
00061 
00062   // NOTE: We based these value as best we could off of the Dalal CVPR 05 Paper.
00063   typedef MyHOG<64, 64, 16, 16, 8, 8, 8, 8, 9> AttributeHOG;
00064   typedef LabColorHistogram<12, 6, 6> AttributeLabHist;
00065   typedef SIFTDes<8,8,4, false> SIFTDescriptor;
00066 
00067   AttributeLearningBaseFeature() { }
00068 
00069   virtual void operator()(cv::Mat& patch, cv::Rect& window)
00070   {
00071     cv::Mat patch_bw(patch.rows, patch.cols,  CV_8UC1);
00072     if (patch.channels() == 3)
00073     {
00074       cv::cvtColor(patch, patch_bw, CV_BGR2GRAY);
00075     }
00076     else
00077     {
00078       patch_bw = patch;
00079     }
00080 
00081     //
00082     // Extract base features
00083     //
00084 
00085 #ifdef USE_CANNY_DESC
00086     ROS_DEBUG_STREAM("Extracting canny descriptor");
00087     std::vector<int> canny_desc = canny_.extractDescriptor(patch, window);
00088 #endif // USE_CANNY_DESC
00089 
00090 #ifdef USE_LAB_DESC
00091     ROS_DEBUG_STREAM("Extracting color descriptor");
00092     std::vector<float> color_desc = col_hist_.extractDescriptor(patch,
00093                                                                 window);
00094 #endif // USE_LAB_DESC
00095 
00096 #ifdef USE_TEXT_DESC
00097     ROS_DEBUG_STREAM("Extracting texture descriptor");
00098     std::vector<int> texture_desc = lmfb_.extractDescriptor(patch_bw);
00099 #endif // USE_TEXT_DESC
00100 
00101 #ifdef USE_HOG_DESC
00102     ROS_DEBUG_STREAM("Extracting HOG descriptor");
00103     std::vector<float> hog_desc = hog_.extractDescriptor(patch, window);
00104 #endif // USE_HOG_DESC
00105 
00106 #ifdef USE_SIFT_DESC
00107     ROS_DEBUG_STREAM("Extracting SIFT descriptor");
00108     std::vector<float> sift_desc = sift_.extractDescriptor(patch, window);
00109     ROS_DEBUG_STREAM("Done extracting SIFT descriptor");
00110 #endif // USE_SIFT_DESC
00111 
00112     //
00113     // Concatenate descriptors into one vector
00114     //
00115     std::vector<float> patch_desc;
00116 
00117 #ifdef USE_CANNY_DESC
00118     ROS_DEBUG_STREAM("Canny descriptor: " << canny_desc.size());
00119     float canny_sum = sum<int>(canny_desc);
00120     for (unsigned int i = 0; i < canny_desc.size(); ++i)
00121     {
00122       patch_desc.push_back(canny_desc[i]);
00123       // ROS_DEBUG_STREAM(i << " : " << canny_desc[i]/canny_sum);
00124     }
00125 #endif // USE_CANNY_DESC
00126 
00127 #ifdef USE_LAB_DESC
00128     ROS_DEBUG_STREAM("Color descriptor: " << color_desc.size());
00129 #ifdef NORMALIZE_VALUES
00130     float color_sum = sum<float>(color_desc);
00131 #endif  // NORMALIZE_VALUES
00132     for (unsigned int i = 0; i < color_desc.size(); ++i)
00133     {
00134 #ifdef NORMALIZE_VALUES
00135       patch_desc.push_back(color_desc[i]/color_sum);
00136 #else
00137       patch_desc.push_back(color_desc[i]);
00138 #endif
00139 
00140       // ROS_DEBUG_STREAM(i << " : " << color_desc[i]/color_sum);
00141     }
00142 #endif // USE_LAB_DESC
00143 
00144 #ifdef USE_TEXT_DESC
00145     ROS_DEBUG_STREAM("Texture descriptor: " << texture_desc.size());
00146 #ifdef NORMALIZE_VALUES
00147     float texture_sum = sum<int>(texture_desc);
00148 #endif  // NORMALIZE_VALUES
00149     for (unsigned int i = 0; i < texture_desc.size(); ++i)
00150     {
00151 #ifdef NORMALIZE_VALUES
00152       patch_desc.push_back(texture_desc[i]/texture_sum);
00153 #else
00154       patch_desc.push_back(texture_desc[i]);
00155 #endif // NORMALIZE_VALUES
00156 
00157 
00158       // ROS_DEBUG_STREAM(i << " : " << texture_desc[i]/texture_sum);
00159     }
00160 #endif //USE_TEXT_DESC
00161 
00162 #ifdef USE_HOG_DESC
00163     ROS_DEBUG_STREAM("HOG descriptor: " << hog_desc.size());
00164     for (unsigned int i = 0; i < hog_desc.size(); ++i)
00165     {
00166       patch_desc.push_back(hog_desc[i]);
00167     }
00168 #endif // USE_HOG_DESC
00169 
00170 #ifdef USE_SIFT_DESC
00171     ROS_DEBUG_STREAM("SIFT descriptor: " << sift_desc.size());
00172     for (unsigned int i = 0; i < sift_desc.size(); ++i)
00173     {
00174       patch_desc.push_back(sift_desc[i]);
00175     }
00176 #endif // USE_HOG_DESC
00177 
00178     ROS_DEBUG_STREAM("Total descriptor: " << patch_desc.size());
00179     descriptor_ = patch_desc;
00180   }
00181 
00182   virtual std::vector<float> getDescriptor() const
00183   {
00184     return descriptor_;
00185   }
00186 
00187   virtual void setTextonFile(std::string texton_file)
00188   {
00189     lmfb_.readTextonCenters(texton_file);
00190   }
00191 
00192   virtual void setSIFTFile(std::string sift_file)
00193   {
00194     if ( sift_.loadClusterCenters(sift_file) )
00195     {
00196       SIFTFeatures centers = sift_.getCenters();
00197       ROS_INFO_STREAM("Loaded " << centers.size() << " centers.");
00198     }
00199   }
00200 
00201  protected:
00202   std::vector<float> descriptor_;
00203   AttributeLabHist col_hist_;
00204   LMFilterBank lmfb_;
00205   CannyEdges canny_;
00206   AttributeHOG hog_;
00207   SIFTDescriptor sift_;
00208 
00209   float normalize(int val_raw, float min_val = 0.0, float max_val = 255.0)
00210   {
00211     // Normalize to the range 0 to 1
00212     return (val_raw - min_val)*2.0/(max_val - min_val);
00213   }
00214 
00215 };
00216 }
00217 #endif // attribute_learning_base_feature_h_DEFINED


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