sift_des_codebook_generation.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/features/sift_des.h>
00036 #include <opencv2/highgui/highgui.hpp>
00037 #include <sstream>
00038 #include <ros/ros.h>
00039 #include <opencv2/ml/ml.hpp>
00040 
00041 using namespace cpl_visual_features;
00042 typedef SIFTDes<8,8,4, false> SIFTDescriptor;
00043 
00044 void usage(std::string exec_name)
00045 {
00046   ROS_ERROR_STREAM("usage: "
00047                    << exec_name
00048                    << " image_path"
00049                    << " image_count"
00050                    << " image_type"
00051                    << " save_path"
00052                    << " [num_centers] [attempts]");
00053 }
00054 
00055 int main(int argc, char** argv)
00056 
00057 {
00058   // Parameters to read from the command line
00059   int img_count = 1;
00060   int num_centers = 20;
00061   int attempts = 1;
00062   std::string img_path = "";
00063   std::string img_sfx = "";
00064   std::string centers_path = "";
00065 
00066   static const int min_args = 5;
00067   static const int max_args = 7;
00068   if (argc < min_args || argc > max_args)
00069   {
00070     usage(argv[0]);
00071     return -1;
00072   }
00073 
00074   img_path = argv[1];
00075   img_count = atoi(argv[2]);
00076   img_sfx = argv[3];
00077   centers_path = argv[4];
00078   if (argc > 5)
00079     num_centers = atoi(argv[5]);
00080   if (argc > 6)
00081     attempts = atoi(argv[6]);
00082   SIFTDescriptor sift;
00083   SIFTFeatures training_features;
00084 
00085   for (int i = 0; i < img_count; i++)
00086   {
00087     std::stringstream filepath;
00088     filepath << img_path << i << "." << img_sfx;
00089 
00090     ROS_INFO_STREAM("Extracting from image " << filepath.str() );
00091 
00092     cv::Mat frame;
00093     frame = cv::imread(filepath.str());
00094     try
00095     {
00096       cv::Mat frame_bw(frame.size(), CV_8UC1);
00097       cv::cvtColor(frame, frame_bw, CV_BGR2GRAY);
00098       SIFTFeatures new_feats = sift.extractRawFeatures(frame_bw);
00099       for (unsigned int j = 0; j < new_feats.size(); ++j)
00100       {
00101         training_features.push_back(new_feats[j]);
00102       }
00103     }
00104     catch(cv::Exception e)
00105     {
00106       ROS_ERROR_STREAM(e.err);
00107     }
00108   }
00109   ROS_INFO_STREAM("Have " << training_features.size() << " total features.");
00110   SIFTFeatures centers = sift.clusterFeatures(training_features,
00111                                               num_centers, attempts);
00112   sift.saveClusterCenters(centers, centers_path);
00113   sift.loadClusterCenters(centers_path);
00114   SIFTFeatures read_centers = sift.getCenters();
00115   if (centers.size() != read_centers.size())
00116   {
00117     ROS_WARN_STREAM("Read and written codebooks have different sizes: "
00118                     << " read: " << read_centers.size()
00119                     << " written: " << centers.size());
00120     return -1;
00121   }
00122 
00123   for (unsigned int i = 0; i < centers.size(); ++i)
00124   {
00125     SIFTFeature a = centers[i];
00126     SIFTFeature b = read_centers[i];
00127     if (a.size() != b.size())
00128     {
00129       ROS_WARN_STREAM("Read cluster center " << i << " has length "
00130                       << b.size());
00131       ROS_WARN_STREAM("Written cluster center " << i << " has length "
00132                       << a.size());
00133       continue;
00134     }
00135     for (unsigned int j = 0; j < a.size(); ++j)
00136     {
00137       // Compare feature elements
00138       if (a[j] != b[j])
00139       {
00140         //ROS_WARN_STREAM("(" << i << ", " << j << "): " << a[j] - b[j]);
00141       }
00142     }
00143   }
00144 
00145   return 0;
00146 }


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