sliding_window.cpp
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 #include <cpl_visual_features/sliding_window.h>
00036 #include <opencv2/highgui/highgui.hpp>
00037 #include <ros/package.h>
00038 #include <sstream>
00039 
00040 #include <cpl_visual_features/saliency/center_surround.h>
00041 #include <cpl_visual_features/features/normalized_sum.h>
00042 #include <cpl_visual_features/features/color_histogram.h>
00043 #include <cpl_visual_features/features/lab_color_histogram.h>
00044 #include <cpl_visual_features/features/color_cells.h>
00045 #include <cpl_visual_features/features/canny_edges.h>
00046 #include <cpl_visual_features/features/my_hog.h>
00047 #include <cpl_visual_features/features/attribute_learning_base_feature.h>
00048 #include <cpl_visual_features/features/sift_des.h>
00049 
00050 // #define RUN_SALIENCY 1
00051 // #define USE_ATT_WINDOW 1
00052 // #define USE_LAB_WINDOW 1
00053 
00054 using cv::Mat;
00055 using cv::Rect;
00056 using cv::Size;
00057 using std::pair;
00058 using std::vector;
00059 using namespace cpl_visual_features;
00060 
00061 typedef ColorHistogram<16> ColorHist16;
00062 typedef MyHOG<64, 64, 8, 8, 8, 8, 4, 4, 9> SWDHog;
00063 typedef LabColorHistogram<24,16,16> LabColorHist16;
00064 typedef SIFTDes<4, 4, 3, true> SIFTDesA;
00065 
00066 void cannyWindow(Mat& frame, vector<pair<int,int> >& windows)
00067 {
00068   SlidingWindowDetector<CannyEdges, CannyEdges::Descriptor> swd;
00069   swd.scanImage(frame, windows);
00070 }
00071 
00072 void hogWindow(Mat& frame, vector<pair<int,int> >& windows)
00073 {
00074   SlidingWindowDetector< SWDHog, SWDHog::Descriptor> swd;
00075   swd.scanImage(frame, windows);
00076   // SWDHog mine;
00077   // cv::Rect r;
00078   // mine(frame, r);
00079 }
00080 
00081 
00082 void siftWindow(Mat& frame, vector<pair<int,int> >& windows)
00083 {
00084   SlidingWindowDetector< SIFTDesA, SIFTDesA::Descriptor> swd;
00085   swd.scanImage(frame, windows);
00086 }
00087 
00088 LabColorHist16::Descriptor labColorHistWindow(Mat& frame, pair<int,int> window)
00089 {
00090   SlidingWindowDetector<LabColorHist16, LabColorHist16::Descriptor> swd;
00091   swd.scanImage(frame, window, true);
00092   return swd.descriptors_[swd.descriptors_.size()-1];
00093 }
00094 
00095 void colorCellWindow(Mat& frame, vector<pair<int,int> >& windows)
00096 {
00097   SlidingWindowDetector<ColorCell, ColorCell::Descriptor> swd;
00098   swd.scanImage(frame, windows[5]);
00099   vector<float> my_desc = swd.feature_.getDescriptor();
00100 }
00101 
00102 int main(int argc, char** argv)
00103 {
00104   int count = 1;
00105   std::string path = "";
00106   bool use_gradient = false;
00107   bool flip_rgb = false;
00108 
00109   if (argc > 1)
00110     path = argv[1];
00111 
00112   if (argc > 2)
00113     count = atoi(argv[2]);
00114 
00115   if (argc > 3)
00116     use_gradient = (atoi(argv[3]) != 0);
00117 
00118   if (argc > 4)
00119     flip_rgb = (atoi(argv[4]) != 0);;
00120 
00121   vector<pair<int,int> > windows;
00122   // windows.push_back(pair<int,int>( 4,  4));
00123   // windows.push_back(pair<int,int>( 8,  8));
00124   // windows.push_back(pair<int,int>( 8,  16));
00125   // windows.push_back(pair<int,int>( 16,  8));
00126   // windows.push_back(pair<int,int>( 8,  32));
00127   // windows.push_back(pair<int,int>( 32,  8));
00128   // windows.push_back(pair<int,int>( 16,  16));
00129   // windows.push_back(pair<int,int>( 16,  32));
00130   // windows.push_back(pair<int,int>( 32,  16));
00131   // windows.push_back(pair<int,int>( 32,  32));
00132   // windows.push_back(pair<int,int>( 64,  32));
00133   // windows.push_back(pair<int,int>( 32,  64));
00134   // windows.push_back(pair<int,int>( 64,  64));
00135   windows.push_back(pair<int,int>( 32, 128));
00136   windows.push_back(pair<int,int>(128,  32));
00137   windows.push_back(pair<int,int>( 64, 128));
00138   windows.push_back(pair<int,int>(128,  64));
00139   windows.push_back(pair<int,int>( 64, 256));
00140   windows.push_back(pair<int,int>(256,  64));
00141   windows.push_back(pair<int,int>(128, 128));
00142   windows.push_back(pair<int,int>(128, 256));
00143 
00144 #ifdef RUN_SALIENCY
00145   SlidingWindowDetector<NormalizedSum, NormalizedSum::Descriptor> swd;
00146   CenterSurroundMapper csm(1, 3, 2, 3);
00147 #endif // RUN_SALIENCY
00148 
00149 #ifdef USE_ATT_WINDOW
00150   SlidingWindowDetector<AttributeLearningBaseFeature,
00151       AttributeLearningBaseFeature::Descriptor> attribute_wd;
00152   std::stringstream texton_path;
00153   std::string package_path = ros::package::getPath( "cpl_visual_features");
00154   texton_path << package_path << "/cfg/textons-500.txt";
00155   attribute_wd.feature_.setTextonFile(texton_path.str());
00156 #endif // USE_ATT_WINDOW
00157 
00158   for (int i = 0; i < count; i++)
00159   {
00160     std::stringstream filepath;
00161     if (count == 1 && path != "")
00162     {
00163       filepath << path;
00164     }
00165 
00166     else if (path != "")
00167     {
00168       filepath << path << i << ".png";
00169     }
00170     else
00171     {
00172       filepath << "/home/thermans/data/robot.jpg";
00173     }
00174     ROS_INFO_STREAM("Image " << i);
00175     Mat frame;
00176     frame = cv::imread(filepath.str());
00177     if (flip_rgb)
00178     {
00179       Mat op_frame(frame.rows, frame.cols, frame.type());
00180       cvtColor(frame, op_frame, CV_RGB2BGR);
00181       op_frame.copyTo(frame);
00182     }
00183     try
00184     {
00185 
00186 
00187       siftWindow(frame, windows);
00188       
00189 #ifdef RUN_SALIENCY
00190       // Get the saliency map
00191       Mat saliency_img = csm(frame, use_gradient);
00192       cv::imshow("saliency map scaled", saliency_img);
00193 
00194       // Find the most salient region
00195       swd.feature_.resetMax();
00196       swd.scanImage(saliency_img, windows);
00197 
00198       // Report what this region is
00199       cv::Rect max_loc = swd.feature_.getMaxLoc();
00200       ROS_INFO_STREAM("max_window_loc: ("
00201                       << max_loc.x << ", " << max_loc.y << ", "
00202                       << max_loc.height << ", " << max_loc.width << ")");
00203 
00204       // Find the most salient pixel and report it
00205       swd.feature_.resetMax();
00206       swd.scanImage(saliency_img, pair<int,int>(1,1));
00207       cv::Rect max_point = swd.feature_.getMaxLoc();
00208       ROS_INFO_STREAM("max_point at: (" << max_point.x << ", " << max_point.y
00209                       << ")");
00210 
00211       // Display stuff
00212       Mat disp_img(frame.rows, frame.cols, frame.type());
00213       frame.copyTo(disp_img);
00214 
00215       int img_scale = frame.cols / saliency_img.cols;
00216       cv::rectangle(disp_img, max_loc.tl()*img_scale, max_loc.br()*img_scale,
00217                     CV_RGB(255,0,0));
00218       cv::rectangle(disp_img, max_point.tl()*img_scale,
00219                     max_point.br()*img_scale,
00220                     CV_RGB(0,255,0));
00221 
00222       cv::imshow("Most salient region", disp_img);
00223       if (i == count - 1)
00224         cv::waitKey();
00225       else
00226         cv::waitKey(30);
00227 #endif // RUN_SALIENCY
00228 #ifdef USE_ATT_WINDOW
00229       attribute_wd.scanImage(frame, pair<int,int>(frame.cols - 1,
00230                                                   frame.rows - 1), true);
00231       vector<float> ab_desc = attribute_wd.descriptors_[0];
00232       attribute_wd.descriptors_.clear();
00233       ROS_INFO_STREAM("Total feature vector size is: " << ab_desc.size());
00234 #endif // USE_ATT_WINDOW
00235 
00236 #ifdef USE_LAB_WINDOW
00237       LabColorHist16::Descriptor des = labColorHistWindow(
00238           frame, pair<int,int>(frame.cols - 1, frame.rows - 1));
00239 
00240       int zero_counts = 0;
00241       for (unsigned int idx = 0; idx < des.size(); ++idx)
00242       {
00243         if ( des[idx] == 0)
00244           ++zero_counts;
00245       }
00246 
00247       ROS_INFO_STREAM("Descriptor has " << zero_counts
00248                       << " empty bins from a total of "
00249                       << des.size() << ".");
00250 #endif // USE_LAB_WINDOW
00251     }
00252     catch(cv::Exception e)
00253     {
00254       ROS_ERROR_STREAM(e.err);
00255     }
00256   }
00257   return 0;
00258 }


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