feature_adjuster.cpp

Felix Endres, 2014-08-19 03:25 pm

Download (6.1 kB)

 
1
/*M///////////////////////////////////////////////////////////////////////////////////////
2
 //
3
 //  IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
4
 //
5
 //  By downloading, copying, installing or using the software you agree to this license.
6
 //  If you do not agree to this license, do not download, install,
7
 //  copy or use the software.
8
 //
9
 //
10
 //                           License Agreement
11
 //                For Open Source Computer Vision Library
12
 //
13
 // Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
14
 // Copyright (C) 2009-2010, Willow Garage Inc., all rights reserved.
15
 // Third party copyrights are property of their respective owners.
16
 //
17
 // Redistribution and use in source and binary forms, with or without modification,
18
 // are permitted provided that the following conditions are met:
19
 //
20
 //   * Redistribution's of source code must retain the above copyright notice,
21
 //     this list of conditions and the following disclaimer.
22
 //
23
 //   * Redistribution's in binary form must reproduce the above copyright notice,
24
 //     this list of conditions and the following disclaimer in the documentation
25
 //     and/or other materials provided with the distribution.
26
 //
27
 //   * The name of the copyright holders may not be used to endorse or promote products
28
 //     derived from this software without specific prior written permission.
29
 //
30
 // This software is provided by the copyright holders and contributors "as is" and
31
 // any express or implied warranties, including, but not limited to, the implied
32
 // warranties of merchantability and fitness for a particular purpose are disclaimed.
33
 // In no event shall the Intel Corporation or contributors be liable for any direct,
34
 // indirect, incidental, special, exemplary, or consequential damages
35
 // (including, but not limited to, procurement of substitute goods or services;
36
 // loss of use, data, or profits; or business interruption) however caused
37
 // and on any theory of liability, whether in contract, strict liability,
38
 // or tort (including negligence or otherwise) arising in any way out of
39
 // the use of this software, even if advised of the possibility of such damage.
40
 //
41
 //M*/
42
43
#include "feature_adjuster.h"
44
//#include "opencv2/features2d/precomp.hpp"
45
#include "opencv2/features2d/features2d.hpp"
46
#include "opencv2/imgproc/imgproc.hpp"
47
48
#include <cassert>
49
#include <iostream>
50
using namespace cv;
51
52
53
DetectorAdjuster::DetectorAdjuster(const char* detector_name, double initial_thresh, double min_thresh, double max_thresh, double increase_factor, double decrease_factor ) :
54
    thresh_(initial_thresh), init_thresh_(initial_thresh),
55
    min_thresh_(min_thresh), max_thresh_(max_thresh),
56
    increase_factor_(increase_factor), decrease_factor_(decrease_factor),
57
    detector_name_(detector_name)
58
{
59
  assert(detector_name_ != NULL && "No detector name given, using SURF");
60
}
61
62
void DetectorAdjuster::detectImpl(const Mat& image, std::vector<KeyPoint>& keypoints, const Mat& mask) const
63
{
64
    Ptr<FeatureDetector> detector = FeatureDetector::create(detector_name_);
65
    if(strcmp(detector_name_, "SURF") == 0){
66
      detector->set("hessianThreshold", thresh_);
67
    }
68
    else if(strcmp(detector_name_, "SIFT") == 0){
69
      detector->set("contrastThreshold", thresh_);
70
    }
71
    else if(strcmp(detector_name_, "FAST") == 0){
72
      detector->set("threshold", static_cast<int>(thresh_));
73
    }
74
    else if(strcmp(detector_name_, "AORB") == 0){
75
      detector->set("fastThreshold", static_cast<int>(thresh_));
76
    }
77
    else {
78
      std::cerr << "Unknown Descriptor, not setting threshold";
79
    }
80
    detector->detect(image, keypoints, mask);
81
}
82
83
void DetectorAdjuster::setDecreaseFactor(double new_factor){
84
  decrease_factor_ = new_factor;
85
}
86
void DetectorAdjuster::setIncreaseFactor(double new_factor){
87
  increase_factor_ = new_factor;
88
}
89
90
void DetectorAdjuster::tooFew(int, int)
91
{
92
    thresh_ *= decrease_factor_;
93
    if (thresh_ < min_thresh_)
94
            thresh_ = min_thresh_;
95
}
96
97
void DetectorAdjuster::tooMany(int, int)
98
{
99
    thresh_ *= increase_factor_;
100
    if (thresh_ > max_thresh_)
101
            thresh_ = max_thresh_;
102
}
103
104
//return whether or not the threshhold is beyond
105
//a useful point
106
bool DetectorAdjuster::good() const
107
{
108
    return (thresh_ > min_thresh_) && (thresh_ < max_thresh_);
109
}
110
111
Ptr<AdjusterAdapter> DetectorAdjuster::clone() const
112
{
113
    Ptr<AdjusterAdapter> cloned_obj(new DetectorAdjuster(detector_name_, init_thresh_, min_thresh_, max_thresh_, increase_factor_, decrease_factor_ ));
114
    return cloned_obj;
115
}
116
117
////////////////////////////////////////////////////////////////////////////////////////////////////////////
118
////////////////////////////////////////////////////////////////////////////////////////////////////////////
119
120
121
DynamicAdaptedFeatureDetectorWithStorage::DynamicAdaptedFeatureDetectorWithStorage(Ptr<AdjusterAdapter> a,
122
                                         int min_features, int max_features, int max_iters ) :
123
        escape_iters_(max_iters), min_features_(min_features), max_features_(max_features), adjuster_(a)
124
{}
125
126
bool DynamicAdaptedFeatureDetectorWithStorage::empty() const
127
{
128
    return !adjuster_ || adjuster_->empty();
129
}
130
131
void DynamicAdaptedFeatureDetectorWithStorage::detectImpl(const cv::Mat& _image, std::vector<KeyPoint>& keypoints, const cv::Mat& _mask) const
132
{
133
    //In contraast to the original, no oscillation testing is needed as
134
    //the loop is broken out of anyway, if too many features were found.
135
136
    //break if the desired number hasn't been reached.
137
    int iter_count = escape_iters_;
138
139
    do { // detect at least once
140
        keypoints.clear();
141
142
        //the adjuster takes care of calling the detector with updated parameters
143
        adjuster_->detect(_image, keypoints,_mask);
144
        if( int(keypoints.size()) < min_features_ )
145
        {
146
            adjuster_->tooFew(min_features_, (int)keypoints.size());
147
        }
148
        else if( int(keypoints.size()) > max_features_ )
149
        {
150
            adjuster_->tooMany(max_features_, (int)keypoints.size());
151
            break;//FIXME: Too many is ok as they are clipped anyway?
152
        }
153
        else
154
            break;
155
156
        iter_count--;
157
    } while( iter_count > 0 && adjuster_->good() );
158
159
}
160
161