TrackBase.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_BASE_H
23 #define OV_CORE_TRACK_BASE_H
24 
25 #include <atomic>
26 #include <iostream>
27 #include <mutex>
28 #include <thread>
29 #include <unordered_map>
30 
31 #include <boost/date_time/posix_time/posix_time.hpp>
32 #include <opencv2/core/core.hpp>
33 #include <opencv2/highgui/highgui.hpp>
34 #include <opencv2/opencv.hpp>
35 
36 #include "utils/colors.h"
37 #include "utils/print.h"
38 #include "utils/sensor_data.h"
39 
40 namespace ov_core {
41 
42 class Feature;
43 class CamBase;
44 class FeatureDatabase;
45 
72 class TrackBase {
73 
74 public:
79 
88  TrackBase(std::unordered_map<size_t, std::shared_ptr<CamBase>> cameras, int numfeats, int numaruco, bool stereo,
89  HistogramMethod histmethod);
90 
91  virtual ~TrackBase() {}
92 
97  virtual void feed_new_camera(const CameraData &message) = 0;
98 
106  virtual void display_active(cv::Mat &img_out, int r1, int g1, int b1, int r2, int g2, int b2, std::string overlay = "");
107 
116  virtual void display_history(cv::Mat &img_out, int r1, int g1, int b1, int r2, int g2, int b2, std::vector<size_t> highlighted = {},
117  std::string overlay = "");
118 
123  std::shared_ptr<FeatureDatabase> get_feature_database() { return database; }
124 
134  void change_feat_id(size_t id_old, size_t id_new);
135 
137  std::unordered_map<size_t, std::vector<cv::KeyPoint>> get_last_obs() {
138  std::lock_guard<std::mutex> lckv(mtx_last_vars);
139  return pts_last;
140  }
141 
143  std::unordered_map<size_t, std::vector<size_t>> get_last_ids() {
144  std::lock_guard<std::mutex> lckv(mtx_last_vars);
145  return ids_last;
146  }
147 
149  int get_num_features() { return num_features; }
150 
152  void set_num_features(int _num_features) { num_features = _num_features; }
153 
154 protected:
156  std::unordered_map<size_t, std::shared_ptr<CamBase>> camera_calib;
157 
159  std::shared_ptr<FeatureDatabase> database;
160 
162  std::map<size_t, bool> camera_fisheye;
163 
166 
169 
172 
174  std::vector<std::mutex> mtx_feeds;
175 
177  std::mutex mtx_last_vars;
178 
180  std::map<size_t, cv::Mat> img_last;
181 
183  std::map<size_t, cv::Mat> img_mask_last;
184 
186  std::unordered_map<size_t, std::vector<cv::KeyPoint>> pts_last;
187 
189  std::unordered_map<size_t, std::vector<size_t>> ids_last;
190 
192  std::atomic<size_t> currid;
193 
194  // Timing variables (most children use these...)
195  boost::posix_time::ptime rT1, rT2, rT3, rT4, rT5, rT6, rT7;
196 };
197 
198 } // namespace ov_core
199 
200 #endif /* OV_CORE_TRACK_BASE_H */
ov_core::TrackBase::mtx_feeds
std::vector< std::mutex > mtx_feeds
Mutexs for our last set of image storage (img_last, pts_last, and ids_last)
Definition: TrackBase.h:174
sensor_data.h
ov_core::TrackBase::currid
std::atomic< size_t > currid
Master ID for this tracker (atomic to allow for multi-threading)
Definition: TrackBase.h:192
ov_core::TrackBase::database
std::shared_ptr< FeatureDatabase > database
Database with all our current features.
Definition: TrackBase.h:159
ov_core::TrackBase::img_mask_last
std::map< size_t, cv::Mat > img_mask_last
Last set of images (use map so all trackers render in the same order)
Definition: TrackBase.h:183
ov_core::TrackBase::mtx_last_vars
std::mutex mtx_last_vars
Mutex for editing the *_last variables.
Definition: TrackBase.h:177
ov_core::TrackBase::HistogramMethod
HistogramMethod
Desired pre-processing image method.
Definition: TrackBase.h:78
ov_core::TrackBase::NONE
@ NONE
Definition: TrackBase.h:78
ov_core::TrackBase::rT3
boost::posix_time::ptime rT3
Definition: TrackBase.h:195
ov_core::TrackBase::feed_new_camera
virtual void feed_new_camera(const CameraData &message)=0
Process a new image.
ov_core::TrackBase::camera_fisheye
std::map< size_t, bool > camera_fisheye
If we are a fisheye model or not.
Definition: TrackBase.h:162
ov_core::TrackBase::use_stereo
bool use_stereo
If we should use binocular tracking or stereo tracking for multi-camera.
Definition: TrackBase.h:168
ov_core::CameraData
Struct for a collection of camera measurements.
Definition: sensor_data.h:55
ov_core::TrackBase::num_features
int num_features
Number of features we should try to track frame to frame.
Definition: TrackBase.h:165
ov_core::TrackBase::TrackBase
TrackBase(std::unordered_map< size_t, std::shared_ptr< CamBase >> cameras, int numfeats, int numaruco, bool stereo, HistogramMethod histmethod)
Public constructor with configuration variables.
Definition: TrackBase.cpp:30
ov_core::TrackBase::set_num_features
void set_num_features(int _num_features)
Setter method for number of active features.
Definition: TrackBase.h:152
ov_core::TrackBase::histogram_method
HistogramMethod histogram_method
What histogram equalization method we should pre-process images with?
Definition: TrackBase.h:171
ov_core::TrackBase::rT7
boost::posix_time::ptime rT7
Definition: TrackBase.h:195
ov_core::TrackBase::get_last_ids
std::unordered_map< size_t, std::vector< size_t > > get_last_ids()
Getter method for active features in the last frame (ids per camera)
Definition: TrackBase.h:143
ov_core::TrackBase::display_active
virtual void display_active(cv::Mat &img_out, int r1, int g1, int b1, int r2, int g2, int b2, std::string overlay="")
Shows features extracted in the last image.
Definition: TrackBase.cpp:43
ov_core::TrackBase::ids_last
std::unordered_map< size_t, std::vector< size_t > > ids_last
Set of IDs of each current feature in the database.
Definition: TrackBase.h:189
print.h
ov_core::TrackBase::CLAHE
@ CLAHE
Definition: TrackBase.h:78
ov_core::TrackBase::rT2
boost::posix_time::ptime rT2
Definition: TrackBase.h:195
ov_core::TrackBase::rT5
boost::posix_time::ptime rT5
Definition: TrackBase.h:195
ov_core::TrackBase::rT1
boost::posix_time::ptime rT1
Definition: TrackBase.h:195
ov_core::TrackBase::change_feat_id
void change_feat_id(size_t id_old, size_t id_new)
Changes the ID of an actively tracked feature to another one.
Definition: TrackBase.cpp:230
ov_core::TrackBase::~TrackBase
virtual ~TrackBase()
Definition: TrackBase.h:91
ov_core::TrackBase::get_last_obs
std::unordered_map< size_t, std::vector< cv::KeyPoint > > get_last_obs()
Getter method for active features in the last frame (observations per camera)
Definition: TrackBase.h:137
colors.h
ov_core::TrackBase::HISTOGRAM
@ HISTOGRAM
Definition: TrackBase.h:78
ov_core::TrackBase::rT6
boost::posix_time::ptime rT6
Definition: TrackBase.h:195
ov_core::TrackBase::get_feature_database
std::shared_ptr< FeatureDatabase > get_feature_database()
Get the feature database with all the track information.
Definition: TrackBase.h:123
ov_core::TrackBase::display_history
virtual void display_history(cv::Mat &img_out, int r1, int g1, int b1, int r2, int g2, int b2, std::vector< size_t > highlighted={}, std::string overlay="")
Shows a "trail" for each feature (i.e. its history)
Definition: TrackBase.cpp:119
ov_core::TrackBase::pts_last
std::unordered_map< size_t, std::vector< cv::KeyPoint > > pts_last
Last set of tracked points.
Definition: TrackBase.h:186
ov_core::TrackBase::get_num_features
int get_num_features()
Getter method for number of active features.
Definition: TrackBase.h:149
ov_core::TrackBase::img_last
std::map< size_t, cv::Mat > img_last
Last set of images (use map so all trackers render in the same order)
Definition: TrackBase.h:180
ov_core::TrackBase::camera_calib
std::unordered_map< size_t, std::shared_ptr< CamBase > > camera_calib
Camera object which has all calibration in it.
Definition: TrackBase.h:156
ov_core
Core algorithms for OpenVINS.
Definition: CamBase.h:30
ov_core::TrackBase
Visual feature tracking base class.
Definition: TrackBase.h:72
ov_core::TrackBase::rT4
boost::posix_time::ptime rT4
Definition: TrackBase.h:195


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