canny_edges.h
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 #ifndef canny_edges_h_DEFINED
00036 #define canny_edges_h_DEFINED
00037 
00038 #include <opencv2/core/core.hpp>
00039 #include <opencv2/imgproc/imgproc.hpp>
00040 #include <opencv2/highgui/highgui.hpp>
00041 #include "abstract_feature.h"
00042 #include <vector>
00043 #include <iostream>
00044 
00045 // #define CANNY_EDGES_SHOW_IMAGES
00046 
00047 namespace cpl_visual_features
00048 {
00049 class CannyEdges : public AbstractFeature<std::vector<int> >
00050 {
00051  public:
00052   CannyEdges(int num_orientations = 8) : num_orientations_(num_orientations),
00053                                          thresh1_(2100.0), thresh2_(2300.0)
00054   {
00055   }
00056 
00057   virtual void operator()(cv::Mat& patch, cv::Rect& window)
00058   {
00059     cv::Mat patch_bw(patch.size(), CV_8UC1);
00060     cv::Mat edges(patch.size(), CV_8UC1);
00061     cv::Mat edges_dx(patch.size(), CV_64FC1);
00062     cv::Mat edges_dy(patch.size(), CV_64FC1);
00063     cv::Mat orientations(patch.size(), CV_64FC1, 0.0);
00064 
00065     if (patch.channels() == 3)
00066     {
00067       cv::cvtColor(patch, patch_bw, CV_BGR2GRAY);
00068     }
00069     else
00070     {
00071       patch_bw = patch;
00072     }
00073 
00074     cv::Canny(patch_bw, edges, thresh1_, thresh2_, 5);
00075 
00076     // Run a Sobel filter on the canny image to get the orientations
00077     cv::Sobel(edges, edges_dx, edges_dx.depth(), 1, 0, 3);
00078     cv::Sobel(edges, edges_dy, edges_dy.depth(), 0, 1, 3);
00079 
00080     // Find the orientation at each pixel
00081     for(int r = 0; r < orientations.rows; ++r)
00082     {
00083       for(int c = 0; c < orientations.cols; ++c)
00084       {
00085         orientations.at<double>(r,c) = atan2(edges_dy.at<double>(r,c),
00086                                              edges_dx.at<double>(r,c));
00087       }
00088     }
00089 
00090     // Quantize the edges orientations into num_orientations_ unsigned bins
00091     std::vector<int> descriptor(num_orientations_, 0);
00092 
00093     for(int r = 0; r < orientations.rows; ++r)
00094     {
00095       for(int c = 0; c < orientations.cols; ++c)
00096       {
00097         // If it is an edge pixel
00098         if (edges.at<uchar>(r,c) != 0)
00099         {
00100           // Increment the correct histogram bin
00101           for (int i = 0; i < num_orientations_; i++)
00102           {
00103             if ( (M_PI/num_orientations_*(i+1)) >=
00104                  std::abs(orientations.at<double>(r,c)) )
00105             {
00106               descriptor[i]++;
00107               break;
00108             }
00109           }
00110         }
00111       }
00112     }
00113 
00114     // Set the class to descriptor to the last extracted one
00115     descriptor_ = descriptor;
00116 
00117 #ifdef CANNY_EDGES_SHOW_IMAGES
00118     //cv::imshow("patch", patch);
00119     cv::imshow("edges", edges);
00120     cv::imshow("edges_dx", edges_dx);
00121     cv::imshow("edges_dy", edges_dy);
00122     cv::imshow("orientations", orientations);
00123     cv::waitKey();
00124 #endif // CANNY_EDGES_SHOW_IMAGES
00125   }
00126 
00127   virtual std::vector<int> getDescriptor() const
00128   {
00129     return descriptor_;
00130   }
00131 
00132  protected:
00133   std::vector<int> descriptor_;
00134   int num_orientations_;
00135   double thresh1_;
00136   double thresh2_;
00137 };
00138 }
00139 #endif // canny_edges_h_DEFINED


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