shape_context.h
Go to the documentation of this file.
00001 // shape_context.cpp : Defines the entry point for the console application.
00002 //
00003 
00004 #ifndef shape_context_h_DEFINED
00005 #define shape_context_h_DEFINED
00006 
00007 #include <opencv2/core/core.hpp>
00008 #include <opencv2/imgproc/imgproc.hpp>
00009 #include <opencv2/highgui/highgui.hpp>
00010 #include <vector>
00011 #include <string>
00012 
00013 namespace cpl_visual_features
00014 {
00015 typedef std::vector<double> ShapeDescriptor;
00016 typedef std::vector<ShapeDescriptor> ShapeDescriptors;
00017 typedef std::vector<int> Path;
00018 typedef std::vector<cv::Point> Samples;
00019 typedef std::vector<cv::Point2f> Samples2f;
00020 
00021 double compareShapes(cv::Mat& imageA, cv::Mat& imageB,
00022                      double epsilonCost = 9e5, bool write_images=false,
00023                      std::string filePath=".", int max_displacement=30,
00024                      std::string filePostFix="");
00025 
00026 std::vector<cv::Point> samplePoints(cv::Mat& edge_image,
00027                                     double percentage = 0.3);
00028 
00029 ShapeDescriptors extractDescriptors(cv::Mat& image);
00030 
00031 ShapeDescriptors constructDescriptors(Samples2f& samples, cv::Point2f& center,
00032                                       bool use_center = false,
00033                                       int radius_bins = 5,
00034                                       int theta_bins = 12,
00035                                       double max_radius = 0,
00036                                       double scale = 100.0);
00037 ShapeDescriptors constructDescriptors(Samples2f& samples,
00038                                       unsigned int radius_bins = 5,
00039                                       unsigned int theta_bins = 12);
00040 
00041 cv::Mat computeCostMatrix(ShapeDescriptors& descriptorsA,
00042                           ShapeDescriptors& descriptorsB,
00043                           double epsilonCost = 9e5,
00044                           bool write_images=false,
00045                           std::string filePath=".", std::string filePostFix="");
00046 
00047 double getMinimumCostPath(cv::Mat& cost_matrix, Path& path);
00048 
00049 void displayMatch(cv::Mat& edge_imgA,
00050                   cv::Mat& edge_imgB,
00051                   Samples& samplesA,
00052                   Samples& samplesB,
00053                   Path& path, int max_displacement=30,
00054                   std::string filePath=".", std::string filePostFix="");
00055 
00056 int getHistogramIndex(double radius, double theta, int radius_bins, int theta_bins);
00057 
00058 template <class sample_type> ShapeDescriptors constructDescriptors(sample_type& samples,
00059                                                                    unsigned int radius_bins = 5,
00060                                                                    unsigned int theta_bins = 12)
00061 {
00062   ShapeDescriptors descriptors;
00063   ShapeDescriptor descriptor;
00064   double max_radius = 0;
00065   double radius, theta;
00066   double x1, x2, y1, y2;
00067   unsigned int i, j, k, m;
00068 
00069   // find maximum radius for normalization purposes
00070   for (i=0; i < samples.size(); i++)
00071   {
00072     x1 = samples.at(i).x;
00073     y1 = samples.at(i).y;
00074     for (k=0; k < samples.size(); k++)
00075     {
00076       if (k != i)
00077       {
00078         x2 = samples.at(k).x;
00079         y2 = samples.at(k).y;
00080 
00081         radius = sqrt(pow(x1-x2,2) + pow(y1-y2,2));
00082         if (radius > max_radius)
00083         {
00084           max_radius = radius;
00085         }
00086       }
00087     }
00088   }
00089   max_radius = log(max_radius);
00090   // std::cout << "Got max_radius of: " << max_radius << std::endl;
00091 
00092   // build a descriptor for each sample
00093   for (i=0; i < samples.size(); i++)
00094   {
00095     // initialize descriptor
00096     descriptor.clear();
00097     for (j=0; j < radius_bins*theta_bins; j++)
00098     {
00099       descriptor.push_back(0);
00100     }
00101     x1 = samples.at(i).x;
00102     y1 = samples.at(i).y;
00103 
00104     // construct descriptor
00105     for (m=0; m < samples.size(); m++)
00106     {
00107       if (m != i)
00108       {
00109         // std::cout << "Constructing descriptor for (" << i << ", " << m << ")" << std::endl;
00110         x2 = samples.at(m).x;
00111         y2 = samples.at(m).y;
00112 
00113         radius = sqrt(pow(x1-x2,2) + pow(y1-y2,2));
00114         radius = log(radius);
00115         radius /= max_radius;
00116         theta = atan2(y1-y2,x1-x2);
00117         theta += M_PI;
00118         theta /= 2*M_PI;
00119         // std::cout << "Getting idx for (" << radius << ", " << theta << ")" << std::endl;
00120         int idx = getHistogramIndex(radius, theta, radius_bins, theta_bins);
00121         // std::cout << "Idx is: " << idx << std::endl;
00122         descriptor.at(idx)++;
00123       }
00124     }
00125 
00126     // add descriptor to std::vector of descriptors
00127     descriptors.push_back(descriptor);
00128   }
00129 
00130   return descriptors;
00131 }
00132 
00133 };
00134 #endif // shape_context_h_DEFINED


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