Skip to content

Commit

Permalink
fixed recording toomany and toofew ratios during mapping
Browse files Browse the repository at this point in the history
  • Loading branch information
rsoussan committed Jul 2, 2024
1 parent ccbc4bc commit 07e874a
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 14 deletions.
8 changes: 4 additions & 4 deletions localization/interest_point/include/interest_point/matching.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ namespace interest_point {
cv::Mat* keypoints_description) = 0;
virtual void TooFew(void) = 0;
virtual void TooMany(void) = 0;
void GetDetectorParams(int & min_features, int & max_features, int & max_retries,
double & min_thresh, double & default_thresh, double & max_thresh);
void GetDetectorParams(int& min_features, int& max_features, int& max_retries, double& min_thresh,
double& default_thresh, double& max_thresh, double& too_many_ratio, double& too_few_ratio);

int last_keypoint_count(void) { return last_keypoint_count_; }

Expand Down Expand Up @@ -80,8 +80,8 @@ namespace interest_point {

std::string GetDetectorName() const {return detector_name_;}

void GetDetectorParams(int & min_features, int & max_features, int & max_retries,
double & min_thresh, double & default_thresh, double & max_thresh);
void GetDetectorParams(int& min_features, int& max_features, int& max_retries, double& min_thresh,
double& default_thresh, double& max_thresh, double& too_many_ratio, double& too_few_ratio);

friend bool operator== (FeatureDetector const& A, FeatureDetector const& B) {
return (A.detector_name_ == B.detector_name_);
Expand Down
13 changes: 8 additions & 5 deletions localization/interest_point/src/matching.cc
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ DEFINE_int32(max_brisk_features, 5000,
"Maximum number of features to be computed using ORGBRISK.");
DEFINE_double(min_brisk_threshold, 10,
"Minimum threshold for feature detection using ORGBRISK.");
DEFINE_double(default_brisk_threshold, 20,
DEFINE_double(default_brisk_threshold, 90,
"Default threshold for feature detection using ORGBRISK.");
DEFINE_double(max_brisk_threshold, 110,
"Maximum threshold for feature detection using ORGBRISK.");
Expand All @@ -94,14 +94,17 @@ DynamicDetector::DynamicDetector(int min_features, int max_features, int max_ret
last_keypoint_count_(0) {}

void DynamicDetector::GetDetectorParams(int& min_features, int& max_features, int& max_retries, double& min_thresh,
double& default_thresh, double& max_thresh) {
double& default_thresh, double& max_thresh, double& too_many_ratio,
double& too_few_ratio) {
min_features = min_features_;
max_features = max_features_;
max_retries = max_retries_;
min_thresh = min_thresh_;
default_thresh = default_thresh_;
max_thresh = max_thresh_;
}
too_many_ratio = too_many_ratio_;
too_few_ratio = too_few_ratio_;
}

void DynamicDetector::Detect(const cv::Mat& image,
std::vector<cv::KeyPoint>* keypoints,
Expand Down Expand Up @@ -268,11 +271,11 @@ void DynamicDetector::GetDetectorParams(int& min_features, int& max_features, in

void FeatureDetector::GetDetectorParams(int & min_features, int & max_features, int & max_retries,
double & min_thresh, double & default_thresh,
double & max_thresh) {
double & max_thresh, double & too_many_ratio, double & too_few_ratio) {
if (detector_ == NULL)
LOG(FATAL) << "The detector was not set.";
detector_->GetDetectorParams(min_features, max_features, max_retries,
min_thresh, default_thresh, max_thresh);
min_thresh, default_thresh, max_thresh, too_many_ratio, too_few_ratio);
}

FeatureDetector::~FeatureDetector(void) {
Expand Down
10 changes: 5 additions & 5 deletions localization/sparse_mapping/src/sparse_map.cc
Original file line number Diff line number Diff line change
Expand Up @@ -711,12 +711,12 @@ void SparseMap::DetectFeatures(const cv::Mat& image,
// map-building, rather than in localization which is more
// performance-sensitive.
int min_features, max_features, max_retries;
double min_thresh, default_thresh, max_thresh;
double min_thresh, default_thresh, max_thresh, too_many_ratio, too_few_ratio;
detector_.GetDetectorParams(min_features, max_features, max_retries,
min_thresh, default_thresh, max_thresh);
interest_point::FeatureDetector local_detector(detector_.GetDetectorName(),
min_features, max_features, max_retries,
min_thresh, default_thresh, max_thresh);
min_thresh, default_thresh, max_thresh, too_many_ratio, too_few_ratio);
interest_point::FeatureDetector local_detector(detector_.GetDetectorName(), min_features, max_features, max_retries,
min_thresh, default_thresh, max_thresh, too_many_ratio,
too_few_ratio);
local_detector.Detect(*image_ptr, &storage, descriptors);
}
mutex_detector_.unlock();
Expand Down

0 comments on commit 07e874a

Please sign in to comment.