ThresholdPolicy.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
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 LABUST nor the names of its
00018  *     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 #include <labust/blueview/ThresholdPolicy.hpp>
00035 #include <opencv2/imgproc/imgproc.hpp>
00036 
00037 using namespace labust::blueview;
00038 
00039 MatPtr SimpleThreshold::threshold(const MatPtr prefiltered, float weight)
00040 {
00041         MatPtr thresholded(new cv::Mat(prefiltered->size(),CV_8UC1));
00042         cv::threshold(*prefiltered, *thresholded, weight, 255, CV_THRESH_BINARY);
00043         thresholded->convertTo(*thresholded,CV_8UC1);
00044         return thresholded;
00045 }
00046 
00047 MatPtr HistThreshold::threshold(const MatPtr prefiltered,
00048                 float min,float max, unsigned char maxVal)
00049 {
00050         enum {thehoodWidth = 1, thehoodHeight = 1};
00051         MatPtr thresholded(new cv::Mat(prefiltered->size(),CV_8U, cv::Scalar(0)));
00052 
00053         size_t width(prefiltered->size().width), height(prefiltered->size().height);
00054 
00055         for(int i=1; i<(width-1); ++i)
00056         {
00057                 for(int j=1; j<(height-1); ++j)
00058                 {
00059                         cv::Mat thehood(*prefiltered,
00060                                         cv::Range(i-thehoodWidth,i+thehoodWidth),
00061                                         cv::Range(j-thehoodHeight,j+thehoodHeight));
00062                         cv::Mat rethood(*prefiltered,
00063                                         cv::Range(i-thehoodWidth,i+thehoodWidth),
00064                                         cv::Range(j-thehoodHeight,j+thehoodHeight));
00065 
00066                         bool flag = false;
00067 
00068                         for (int k=0; k<(thehoodWidth*2 + 1); ++k)
00069                         {
00070                                 for (int k2=0; k2<(thehoodHeight*2 + 1); ++k2)
00071                                 {
00072                                         //std::cout<<"Pixel val:"<<thehood.at<float>(k,k2)<<std::endl;
00073                                         if ((flag = thehood.at<float>(k,k2) >= max)) break;
00074                                 }
00075                         }
00076 
00077                         if (flag)
00078                         {
00079                                 for (int k=0; k<(thehoodWidth*2 + 1); ++k)
00080                                 {
00081                                         for (int k2=0; k2<(thehoodHeight*2 + 1); ++k2)
00082                                         {
00083                                                 if (thehood.at<float>(k,k2) >= min)
00084                                                 {
00085                                                         rethood.at<float>(k,k2) = maxVal;
00086                                                 }
00087                                                 else
00088                                                 {
00089                                                         rethood.at<float>(k,k2) = 0;
00090                                                 }
00091                                         }
00092                                 }
00093                         }
00094                         else
00095                         {
00096                                 cv::Mat(3,3,CV_8U,cv::Scalar(0)).copyTo(rethood);
00097                         }
00098                 }
00099         }
00100 
00101         return thresholded;
00102 }
00103 
00104 
00105 


target_detector
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:05