texture_test.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 <cpl_visual_features/features/lm_filter_bank.h>
00041 #include <ros/package.h>
00042 #include <time.h> // for srand(time(NULL))
00043 #include <cstdlib> // for MAX_RAND
00044 #include <string>
00045 
00046 using cv::Mat;
00047 using cv::Rect;
00048 using cv::Size;
00049 using std::pair;
00050 using std::vector;
00051 using namespace cpl_visual_features;
00052 
00053 
00054 int main(int argc, char** argv)
00055 {
00056   srand(time(NULL));
00057   int count = 1;
00058   std::string path = "";
00059   bool flip_rgb = false;
00060 
00061   if (argc > 1)
00062     path = argv[1];
00063 
00064   if (argc > 2)
00065     count = atoi(argv[2]);
00066 
00067   if (argc > 3)
00068     flip_rgb = (atoi(argv[3]) != 0);
00069 
00070   std::stringstream texton_path;
00071   if (argc > 4)
00072   {
00073     texton_path.clear();
00074     texton_path << argv[4];
00075   }
00076   else
00077   {
00078     std::string package_path = ros::package::getPath( "cpl_visual_features");
00079     texton_path << package_path << "/cfg/textons-500.txt";
00080   }
00081 
00082   std::cout << "Building filters" << std::endl;
00083   LMFilterBank lfb;
00084   if (! lfb.readTextonCenters(texton_path.str()) ) return -1;
00085 
00086   vector<cv::Scalar> colors;
00087   for (int i = 0; i < count; i++)
00088   {
00089     std::stringstream filepath;
00090     if (count == 1 && path != "")
00091     {
00092       filepath << path;
00093     }
00094 
00095     else if (path != "")
00096     {
00097       filepath << path << i << ".png";
00098     }
00099     else
00100     {
00101       filepath << "/home/thermans/data/robot.jpg";
00102     }
00103     std::cout << "Image " << i << std::endl;
00104     Mat frame;
00105     frame = cv::imread(filepath.str());
00106     if (flip_rgb)
00107     {
00108       Mat op_frame(frame.rows, frame.cols, frame.type());
00109       cvtColor(frame, op_frame, CV_RGB2BGR);
00110       op_frame.copyTo(frame);
00111     }
00112     try
00113     {
00114 
00115       // vector<int> hist = lfb.extractDescriptor(frame);
00116       // for (unsigned int j = 0; j < hist.size(); ++j)
00117       // {
00118       //   std::cout << "\t[" << j << "]:" << hist[j] << std::endl;
00119       // }
00120 
00121       // Create max_val random colors
00122       Mat lbl_img = lfb.textonQuantizeImage(frame);
00123 
00124       int max_lbl = lfb.getNumCenters();
00125       std::cout << "Have " << max_lbl << " codewords." << std::endl;
00126 
00127       std::vector<int> texture_feat_vect = lfb.extractDescriptor(frame);
00128       int empty_bin_count = 0;
00129       for (unsigned int idx = 0; idx < texture_feat_vect.size(); ++idx)
00130       {
00131         // TODO: Look at sparsity / distribution of textures.
00132         if (texture_feat_vect[idx] <  1)
00133           ++empty_bin_count;
00134       }
00135       ROS_INFO_STREAM("There are " << empty_bin_count << " empty histogram bins.");
00136 
00137       if (colors.size() != static_cast<unsigned int>(max_lbl)+1)
00138       {
00139         for (int lbl = 0; lbl <= max_lbl; ++lbl)
00140         {
00141           cv::Scalar rand_color;
00142           rand_color[0] = (static_cast<float>(rand()) /
00143                            static_cast<float>(RAND_MAX));
00144           rand_color[1] = (static_cast<float>(rand()) /
00145                            static_cast<float>(RAND_MAX));
00146           rand_color[2] = (static_cast<float>(rand()) /
00147                            static_cast<float>(RAND_MAX));
00148           colors.push_back(rand_color);
00149         }
00150       }
00151       // Create a color image using the label colors
00152       Mat lbl_img_color_r(lbl_img.rows, lbl_img.cols, CV_32FC1);
00153       Mat lbl_img_color_g(lbl_img.rows, lbl_img.cols, CV_32FC1);
00154       Mat lbl_img_color_b(lbl_img.rows, lbl_img.cols, CV_32FC1);
00155 
00156       for (int r = 0; r < lbl_img.rows; ++r)
00157       {
00158         for (int c = 0; c < lbl_img.cols; ++c)
00159         {
00160           int color_idx = static_cast<int>(lbl_img.at<uchar>(r,c));
00161           // std::cout << "Label is: " << color_idx << std::endl;
00162           lbl_img_color_b.at<float>(r,c) = colors[color_idx][0];
00163           lbl_img_color_g.at<float>(r,c) = colors[color_idx][1];
00164           lbl_img_color_r.at<float>(r,c) = colors[color_idx][2];
00165         }
00166       }
00167       vector<Mat> lbl_img_colors;
00168       lbl_img_colors.push_back(lbl_img_color_b);
00169       lbl_img_colors.push_back(lbl_img_color_g);
00170       lbl_img_colors.push_back(lbl_img_color_r);
00171       Mat lbl_img_color(lbl_img.rows, lbl_img.cols, CV_32FC3);
00172 
00173       cv::merge(lbl_img_colors, lbl_img_color);
00174       // Show the original image as well as the colored one.
00175       cv::imshow("Image", frame);
00176       cv::imshow("Textures", lbl_img_color);
00177       cv::waitKey();
00178     }
00179     catch(cv::Exception e)
00180     {
00181       std::cerr << e.err << std::endl;
00182     }
00183   }
00184 
00185   // vector<TextonFeature> tf = lfb.getCenters();
00186   return 0;
00187 }


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