run_saliency.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 <opencv2/highgui/highgui.hpp>
00036 #include <sstream>
00037 
00038 #include <cpl_visual_features/saliency/center_surround.h>
00039 #include <cpl_visual_features/features/gabor_filter_bank.h>
00040 #include <time.h> // for srand(time(NULL))
00041 #include <cstdlib> // for MAX_RAND
00042 
00043 using cv::Mat;
00044 using cv::Rect;
00045 using cv::Size;
00046 using std::pair;
00047 using std::vector;
00048 using namespace cpl_visual_features;
00049 
00050 
00051 int main(int argc, char** argv)
00052 {
00053   srand(time(NULL));
00054   int count = 1;
00055   std::string path = "";
00056   bool use_depth = false;
00057   if (argc > 1)
00058     path = argv[1];
00059 
00060   if (argc > 2)
00061     count = atoi(argv[2]);
00062 
00063   if (argc > 3)
00064   {
00065     use_depth = true;
00066   }
00067 
00068   CenterSurroundMapper csm(2,4,3,4);
00069 
00070   // std::vector<int> is;
00071   // is.push_back(74);
00072   // is.push_back(70);
00073   // is.push_back(18);
00074   // is.push_back(10);
00075   // for (int k = 0; k < is.size(); k++)
00076   for (int i = 0; i < count; i++)
00077   {
00078     // int i = is[k];
00079     std::stringstream filepath;
00080     std::stringstream depth_filepath;
00081     std::stringstream outpath;
00082     if (count == 1 && path != "")
00083     {
00084       filepath << path;
00085     }
00086 
00087     else if (path != "")
00088     {
00089       filepath << path << "color" << std::max(i,0) << ".png";
00090       if (use_depth)
00091       {
00092         depth_filepath << path << std::max(i,0) << "_depth.png";
00093         outpath << path << std::max(i,0) << "_ic_depth.png";
00094       }
00095       else
00096       {
00097         outpath << path << "result_base/img_";
00098         if (i > 9)
00099         {
00100           outpath << "00";
00101         }
00102         else
00103         {
00104           outpath << "000";
00105         }
00106         outpath << std::max(i,0) << "_itti.png";
00107       }
00108     }
00109     else
00110     {
00111       //filepath << "/home/thermans/data/test_images/robot.jpg";
00112       filepath << "/home/thermans/data/test_images/saliency_test_frame.png";
00113       depth_filepath << "/home/thermans/data/test_images/saliency_test_depth_frame.png";
00114       use_depth = true;
00115     }
00116 
00117     std::cout << "Image " << i << std::endl;
00118     std::cout << "\tloc: " << filepath.str() << std::endl;
00119     Mat frame;
00120     frame = cv::imread(filepath.str());
00121     // Mat frame;
00122     cv::imshow("frame", frame);
00123     Mat depth_frame;
00124     if (use_depth)
00125     {
00126       std::cout << "\tdepth loc: " << depth_filepath.str() << std::endl;
00127       depth_frame = cv::imread(depth_filepath.str(), CV_8UC1);
00128       cv::imshow("depth", depth_frame);
00129     }
00130     cv::waitKey(3);
00131     try
00132     {
00133       Mat saliency_map;
00134       bool max_zero = true;
00135       if (use_depth)
00136       {
00137         saliency_map = csm(frame, depth_frame);
00138       }
00139       else
00140       {
00141         saliency_map = csm(frame, false);
00142       }
00143       // TODO: crop before writing
00144       cv::Rect crop_rect(10, 30, 591, 431);
00145       std::cout << "crop_rect.x " << crop_rect.x << std::endl;
00146       std::cout << "crop_rect.y " << crop_rect.y << std::endl;
00147       std::cout << "crop_rect.width " << crop_rect.width << std::endl;
00148       std::cout << "crop_rect.height " << crop_rect.height << std::endl;
00149       cv::Mat cropped_map = saliency_map(crop_rect);
00150       cv::imshow("saliency", saliency_map);
00151       cv::imshow("saliency cropped", cropped_map);
00152       double max_val = 0;
00153       double min_val= 0;
00154       cv::minMaxLoc(cropped_map, &min_val, &max_val);
00155       max_zero = (max_val == 0);
00156       cv::waitKey(0);
00157       cv::imwrite(outpath.str(), cropped_map);
00158     }
00159     catch(cv::Exception e)
00160     {
00161       std::cerr << e.err << std::endl;
00162     }
00163   }
00164 
00165   return 0;
00166 }


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