sliding_window.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 sliding_window_h_DEFINED
00036 #define sliding_window_h_DEFINED
00037 
00038 #include <ros/common.h> // include ROS_ASSERT
00039 #include <opencv2/core/core.hpp>
00040 #include <vector>
00041 #include <utility>
00042 
00043 namespace cpl_visual_features
00044 {
00045 template<class FeatureType, class DescriptorType> class SlidingWindowDetector
00046 {
00047  public:
00051   SlidingWindowDetector() : feature_()
00052   {
00053     windows_.clear();
00054   }
00055 
00062   void scanImage(cv::Mat& img, bool save_desc = false, int step_size = 1)
00063   {
00064     for (unsigned int i = 0; i < windows_.size(); ++i)
00065     {
00066       scanImage(img, windows_[i].first, windows_[i].second, save_desc,
00067                 step_size);
00068     }
00069   }
00070 
00078   void scanImage(cv::Mat& img, std::vector<std::pair<int, int> >& windows,
00079                  bool save_desc = false, int step_size = 1)
00080   {
00081     for (unsigned int i = 0; i < windows.size(); ++i)
00082     {
00083       scanImage(img, windows[i].first, windows[i].second, save_desc, step_size);
00084     }
00085   }
00086 
00093   void scanImage(cv::Mat& img, std::pair<int,int> window_size,
00094                  bool save_desc = false, int step_size = 1)
00095   {
00096     scanImage(img, window_size.first, window_size.second, save_desc, step_size);
00097   }
00098 
00107   void scanImage(cv::Mat& img, int window_width, int window_height,
00108                  bool save_desc = false, int step_size = 1)
00109   {
00110     // Scan the window horizontally first
00111     for (int r = 0; r + window_height < img.rows; r += step_size)
00112     {
00113       for (int c = 0; c + window_width < img.cols; c += step_size)
00114       {
00115         cv::Rect roi(c, r, window_width, window_height);
00116         cv::Mat window = img(roi);
00117         feature_(window, roi);
00118         if (save_desc)
00119         {
00120           DescriptorType d;
00121           d = feature_.getDescriptor();
00122           descriptors_.push_back(d);
00123         }
00124       }
00125     }
00126   }
00127 
00128   void setWindowSizes(std::vector<std::pair<int, int> > windows)
00129   {
00130     windows_ = windows;
00131   }
00132 
00133  protected:
00134   std::vector<std::pair<int, int> > windows_;
00135 
00136  public:
00137   FeatureType feature_;
00138   std::vector<DescriptorType> descriptors_;
00139 };
00140 }
00141 #endif // sliding_window_h_DEFINED


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