TrackDescriptor.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_CORE_TRACK_DESC_H
23 #define OV_CORE_TRACK_DESC_H
24 
25 #include "TrackBase.h"
26 
27 namespace ov_core {
28 
37 class TrackDescriptor : public TrackBase {
38 
39 public:
53  explicit TrackDescriptor(std::unordered_map<size_t, std::shared_ptr<CamBase>> cameras, int numfeats, int numaruco, bool stereo,
54  HistogramMethod histmethod, int fast_threshold, int gridx, int gridy, int minpxdist, double knnratio)
55  : TrackBase(cameras, numfeats, numaruco, stereo, histmethod), threshold(fast_threshold), grid_x(gridx), grid_y(gridy),
56  min_px_dist(minpxdist), knn_ratio(knnratio) {}
57 
62  void feed_new_camera(const CameraData &message) override;
63 
64 protected:
70  void feed_monocular(const CameraData &message, size_t msg_id);
71 
78  void feed_stereo(const CameraData &message, size_t msg_id_left, size_t msg_id_right);
79 
93  void perform_detection_monocular(const cv::Mat &img0, const cv::Mat &mask0, std::vector<cv::KeyPoint> &pts0, cv::Mat &desc0,
94  std::vector<size_t> &ids0);
95 
116  void perform_detection_stereo(const cv::Mat &img0, const cv::Mat &img1, const cv::Mat &mask0, const cv::Mat &mask1,
117  std::vector<cv::KeyPoint> &pts0, std::vector<cv::KeyPoint> &pts1, cv::Mat &desc0, cv::Mat &desc1,
118  size_t cam_id0, size_t cam_id1, std::vector<size_t> &ids0, std::vector<size_t> &ids1);
119 
135  void robust_match(const std::vector<cv::KeyPoint> &pts0, const std::vector<cv::KeyPoint> &pts1, const cv::Mat &desc0,
136  const cv::Mat &desc1, size_t id0, size_t id1, std::vector<cv::DMatch> &matches);
137 
138  // Helper functions for the robust_match function
139  // Original code is from the "RobustMatcher" in the opencv examples
140  // https://github.com/opencv/opencv/blob/master/samples/cpp/tutorial_code/calib3d/real_time_pose_estimation/src/RobustMatcher.cpp
141  void robust_ratio_test(std::vector<std::vector<cv::DMatch>> &matches);
142  void robust_symmetry_test(std::vector<std::vector<cv::DMatch>> &matches1, std::vector<std::vector<cv::DMatch>> &matches2,
143  std::vector<cv::DMatch> &good_matches);
144 
145  // Timing variables
146  boost::posix_time::ptime rT1, rT2, rT3, rT4, rT5, rT6, rT7;
147 
148  // Our orb extractor
149  cv::Ptr<cv::ORB> orb0 = cv::ORB::create();
150  cv::Ptr<cv::ORB> orb1 = cv::ORB::create();
151 
152  // Our descriptor matcher
153  cv::Ptr<cv::DescriptorMatcher> matcher = cv::DescriptorMatcher::create("BruteForce-Hamming");
154 
155  // Parameters for our FAST grid detector
157  int grid_x;
158  int grid_y;
159 
160  // Minimum pixel distance to be "far away enough" to be a different extracted feature
162 
163  // The ratio between two kNN matches, if that ratio is larger then this threshold
164  // then the two features are too close, so should be considered ambiguous/bad match
165  double knn_ratio;
166 
167  // Descriptor matrices
168  std::unordered_map<size_t, cv::Mat> desc_last;
169 };
170 
171 } // namespace ov_core
172 
173 #endif /* OV_CORE_TRACK_DESC_H */
ov_core::TrackDescriptor::rT6
boost::posix_time::ptime rT6
Definition: TrackDescriptor.h:146
ov_core::TrackDescriptor::robust_symmetry_test
void robust_symmetry_test(std::vector< std::vector< cv::DMatch >> &matches1, std::vector< std::vector< cv::DMatch >> &matches2, std::vector< cv::DMatch > &good_matches)
Definition: TrackDescriptor.cpp:554
ov_core::TrackBase::HistogramMethod
HistogramMethod
Desired pre-processing image method.
Definition: TrackBase.h:78
ov_core::TrackDescriptor::robust_ratio_test
void robust_ratio_test(std::vector< std::vector< cv::DMatch >> &matches)
Definition: TrackDescriptor.cpp:538
TrackBase.h
ov_core::TrackDescriptor::orb0
cv::Ptr< cv::ORB > orb0
Definition: TrackDescriptor.h:149
ov_core::CameraData
Struct for a collection of camera measurements.
Definition: sensor_data.h:55
ov_core::TrackDescriptor::robust_match
void robust_match(const std::vector< cv::KeyPoint > &pts0, const std::vector< cv::KeyPoint > &pts1, const cv::Mat &desc0, const cv::Mat &desc1, size_t id0, size_t id1, std::vector< cv::DMatch > &matches)
Find matches between two keypoint+descriptor sets.
Definition: TrackDescriptor.cpp:480
ov_core::TrackDescriptor::knn_ratio
double knn_ratio
Definition: TrackDescriptor.h:165
ov_core::TrackDescriptor::grid_y
int grid_y
Definition: TrackDescriptor.h:158
ov_core::TrackDescriptor::rT4
boost::posix_time::ptime rT4
Definition: TrackDescriptor.h:146
ov_core::TrackDescriptor::feed_monocular
void feed_monocular(const CameraData &message, size_t msg_id)
Process a new monocular image.
Definition: TrackDescriptor.cpp:63
ov_core::TrackDescriptor::feed_stereo
void feed_stereo(const CameraData &message, size_t msg_id_left, size_t msg_id_right)
Process new stereo pair of images.
Definition: TrackDescriptor.cpp:180
ov_core::TrackDescriptor::orb1
cv::Ptr< cv::ORB > orb1
Definition: TrackDescriptor.h:150
ov_core::TrackDescriptor::rT7
boost::posix_time::ptime rT7
Definition: TrackDescriptor.h:146
ov_core::TrackDescriptor::rT2
boost::posix_time::ptime rT2
Definition: TrackDescriptor.h:146
ov_core::TrackDescriptor::perform_detection_monocular
void perform_detection_monocular(const cv::Mat &img0, const cv::Mat &mask0, std::vector< cv::KeyPoint > &pts0, cv::Mat &desc0, std::vector< size_t > &ids0)
Detects new features in the current image.
Definition: TrackDescriptor.cpp:355
ov_core::TrackDescriptor::rT1
boost::posix_time::ptime rT1
Definition: TrackDescriptor.h:146
ov_core::TrackDescriptor::rT5
boost::posix_time::ptime rT5
Definition: TrackDescriptor.h:146
ov_core::TrackDescriptor::grid_x
int grid_x
Definition: TrackDescriptor.h:157
ov_core::TrackDescriptor::feed_new_camera
void feed_new_camera(const CameraData &message) override
Process a new image.
Definition: TrackDescriptor.cpp:33
ov_core::TrackDescriptor::threshold
int threshold
Definition: TrackDescriptor.h:156
ov_core::TrackDescriptor::perform_detection_stereo
void perform_detection_stereo(const cv::Mat &img0, const cv::Mat &img1, const cv::Mat &mask0, const cv::Mat &mask1, std::vector< cv::KeyPoint > &pts0, std::vector< cv::KeyPoint > &pts1, cv::Mat &desc0, cv::Mat &desc1, size_t cam_id0, size_t cam_id1, std::vector< size_t > &ids0, std::vector< size_t > &ids1)
Detects new features in the current stereo pair.
Definition: TrackDescriptor.cpp:403
ov_core::TrackDescriptor::desc_last
std::unordered_map< size_t, cv::Mat > desc_last
Definition: TrackDescriptor.h:168
ov_core::TrackDescriptor::matcher
cv::Ptr< cv::DescriptorMatcher > matcher
Definition: TrackDescriptor.h:153
ov_core::TrackDescriptor::rT3
boost::posix_time::ptime rT3
Definition: TrackDescriptor.h:146
ov_core::TrackDescriptor
Descriptor-based visual tracking.
Definition: TrackDescriptor.h:37
ov_core::TrackDescriptor::min_px_dist
int min_px_dist
Definition: TrackDescriptor.h:161
ov_core
Core algorithms for OpenVINS.
Definition: CamBase.h:30
ov_core::TrackBase
Visual feature tracking base class.
Definition: TrackBase.h:72
ov_core::TrackDescriptor::TrackDescriptor
TrackDescriptor(std::unordered_map< size_t, std::shared_ptr< CamBase >> cameras, int numfeats, int numaruco, bool stereo, HistogramMethod histmethod, int fast_threshold, int gridx, int gridy, int minpxdist, double knnratio)
Public constructor with configuration variables.
Definition: TrackDescriptor.h:53


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17