TrackAruco.cpp
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 #include "TrackAruco.h"
23 
24 #include "cam/CamBase.h"
25 #include "feat/Feature.h"
26 #include "feat/FeatureDatabase.h"
28 
29 using namespace ov_core;
30 
32 
33  // Error check that we have all the data
34  if (message.sensor_ids.empty() || message.sensor_ids.size() != message.images.size() || message.images.size() != message.masks.size()) {
35  PRINT_ERROR(RED "[ERROR]: MESSAGE DATA SIZES DO NOT MATCH OR EMPTY!!!\n" RESET);
36  PRINT_ERROR(RED "[ERROR]: - message.sensor_ids.size() = %zu\n" RESET, message.sensor_ids.size());
37  PRINT_ERROR(RED "[ERROR]: - message.images.size() = %zu\n" RESET, message.images.size());
38  PRINT_ERROR(RED "[ERROR]: - message.masks.size() = %zu\n" RESET, message.masks.size());
39  std::exit(EXIT_FAILURE);
40  }
41 
42  // There is not such thing as stereo tracking for aruco
43  // Thus here we should just call the monocular version two times
44 #if ENABLE_ARUCO_TAGS
45  size_t num_images = message.images.size();
46  parallel_for_(cv::Range(0, (int)num_images), LambdaBody([&](const cv::Range &range) {
47  for (int i = range.start; i < range.end; i++) {
48  perform_tracking(message.timestamp, message.images.at(i), message.sensor_ids.at(i), message.masks.at(i));
49  }
50  }));
51 #else
52  PRINT_ERROR(RED "[ERROR]: you have not compiled with aruco tag support!!!\n" RESET);
53  std::exit(EXIT_FAILURE);
54 #endif
55 }
56 
57 #if ENABLE_ARUCO_TAGS
58 
59 void TrackAruco::perform_tracking(double timestamp, const cv::Mat &imgin, size_t cam_id, const cv::Mat &maskin) {
60 
61  // Start timing
62  rT1 = boost::posix_time::microsec_clock::local_time();
63 
64  // Lock this data feed for this camera
65  std::lock_guard<std::mutex> lck(mtx_feeds.at(cam_id));
66 
67  // Histogram equalize
68  cv::Mat img;
69  if (histogram_method == HistogramMethod::HISTOGRAM) {
70  cv::equalizeHist(imgin, img);
71  } else if (histogram_method == HistogramMethod::CLAHE) {
72  double eq_clip_limit = 10.0;
73  cv::Size eq_win_size = cv::Size(8, 8);
74  cv::Ptr<cv::CLAHE> clahe = cv::createCLAHE(eq_clip_limit, eq_win_size);
75  clahe->apply(imgin, img);
76  } else {
77  img = imgin;
78  }
79 
80  // Clear the old data from the last timestep
81  ids_aruco[cam_id].clear();
82  corners[cam_id].clear();
83  rejects[cam_id].clear();
84 
85  // If we are downsizing, then downsize
86  cv::Mat img0;
87  if (do_downsizing) {
88  cv::pyrDown(img, img0, cv::Size(img.cols / 2, img.rows / 2));
89  } else {
90  img0 = img;
91  }
92 
93  //===================================================================================
94  //===================================================================================
95 
96  // Perform extraction
97 #if CV_MAJOR_VERSION > 4 || ( CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION >= 7)
98  aruco_detector.detectMarkers(img0, corners[cam_id], ids_aruco[cam_id], rejects[cam_id]);
99 #else
100  cv::aruco::detectMarkers(img0, aruco_dict, corners[cam_id], ids_aruco[cam_id], aruco_params, rejects[cam_id]);
101 #endif
102  rT2 = boost::posix_time::microsec_clock::local_time();
103 
104  //===================================================================================
105  //===================================================================================
106 
107  // If we downsized, scale all our u,v measurements by a factor of two
108  // Note: we do this so we can use these results for visulization later
109  // Note: and so that the uv added is in the same image size
110  if (do_downsizing) {
111  for (size_t i = 0; i < corners[cam_id].size(); i++) {
112  for (size_t j = 0; j < corners[cam_id].at(i).size(); j++) {
113  corners[cam_id].at(i).at(j).x *= 2;
114  corners[cam_id].at(i).at(j).y *= 2;
115  }
116  }
117  for (size_t i = 0; i < rejects[cam_id].size(); i++) {
118  for (size_t j = 0; j < rejects[cam_id].at(i).size(); j++) {
119  rejects[cam_id].at(i).at(j).x *= 2;
120  rejects[cam_id].at(i).at(j).y *= 2;
121  }
122  }
123  }
124 
125  //===================================================================================
126  //===================================================================================
127 
128  // ID vectors, of all currently tracked IDs
129  std::vector<size_t> ids_new;
130  std::vector<cv::KeyPoint> pts_new;
131 
132  // Append to our feature database this new information
133  for (size_t i = 0; i < ids_aruco[cam_id].size(); i++) {
134  // Skip if ID is greater then our max
135  if (ids_aruco[cam_id].at(i) > max_tag_id)
136  continue;
137  // Assert we have 4 points (we will only use one of them)
138  assert(corners[cam_id].at(i).size() == 4);
139  for (int n = 0; n < 4; n++) {
140  // Check if it is in the mask
141  // NOTE: mask has max value of 255 (white) if it should be
142  if (maskin.at<uint8_t>((int)corners[cam_id].at(i).at(n).y, (int)corners[cam_id].at(i).at(n).x) > 127)
143  continue;
144  // Try to undistort the point
145  cv::Point2f npt_l = camera_calib.at(cam_id)->undistort_cv(corners[cam_id].at(i).at(n));
146  // Append to the ids vector and database
147  size_t tmp_id = (size_t)ids_aruco[cam_id].at(i) + n * max_tag_id;
148  database->update_feature(tmp_id, timestamp, cam_id, corners[cam_id].at(i).at(n).x, corners[cam_id].at(i).at(n).y, npt_l.x, npt_l.y);
149  // Append to active tracked point list
150  cv::KeyPoint kpt;
151  kpt.pt = corners[cam_id].at(i).at(n);
152  ids_new.push_back(tmp_id);
153  pts_new.push_back(kpt);
154  }
155  }
156 
157  // Move forward in time
158  {
159  std::lock_guard<std::mutex> lckv(mtx_last_vars);
160  img_last[cam_id] = img;
161  img_mask_last[cam_id] = maskin;
162  ids_last[cam_id] = ids_new;
163  pts_last[cam_id] = pts_new;
164  }
165  rT3 = boost::posix_time::microsec_clock::local_time();
166 
167  // Timing information
168  PRINT_ALL("[TIME-ARUCO]: %.4f seconds for detection\n", (rT2 - rT1).total_microseconds() * 1e-6);
169  PRINT_ALL("[TIME-ARUCO]: %.4f seconds for feature DB update (%d features)\n", (rT3 - rT2).total_microseconds() * 1e-6,
170  (int)ids_new.size());
171  PRINT_ALL("[TIME-ARUCO]: %.4f seconds for total\n", (rT3 - rT1).total_microseconds() * 1e-6);
172 }
173 
174 void TrackAruco::display_active(cv::Mat &img_out, int r1, int g1, int b1, int r2, int g2, int b2, std::string overlay) {
175 
176  // Cache the images to prevent other threads from editing while we viz (which can be slow)
177  std::map<size_t, cv::Mat> img_last_cache, img_mask_last_cache;
178  {
179  std::lock_guard<std::mutex> lckv(mtx_last_vars);
180  img_last_cache = img_last;
181  img_mask_last_cache = img_mask_last;
182  }
183  auto ids_aruco_cache = ids_aruco;
184  auto corners_cache = corners;
185  auto rejects_cache = rejects;
186 
187  // Get the largest width and height
188  int max_width = -1;
189  int max_height = -1;
190  for (auto const &pair : img_last_cache) {
191  if (max_width < pair.second.cols)
192  max_width = pair.second.cols;
193  if (max_height < pair.second.rows)
194  max_height = pair.second.rows;
195  }
196 
197  // Return if we didn't have a last image
198  if (img_last_cache.empty() || max_width == -1 || max_height == -1)
199  return;
200 
201  // If the image is "small" thus we shoudl use smaller display codes
202  bool is_small = (std::min(max_width, max_height) < 400);
203 
204  // If the image is "new" then draw the images from scratch
205  // Otherwise, we grab the subset of the main image and draw on top of it
206  bool image_new = ((int)img_last_cache.size() * max_width != img_out.cols || max_height != img_out.rows);
207 
208  // If new, then resize the current image
209  if (image_new)
210  img_out = cv::Mat(max_height, (int)img_last_cache.size() * max_width, CV_8UC3, cv::Scalar(0, 0, 0));
211 
212  // Loop through each image, and draw
213  int index_cam = 0;
214  for (auto const &pair : img_last_cache) {
215  // select the subset of the image
216  cv::Mat img_temp;
217  if (image_new)
218  cv::cvtColor(img_last_cache[pair.first], img_temp, cv::COLOR_GRAY2RGB);
219  else
220  img_temp = img_out(cv::Rect(max_width * index_cam, 0, max_width, max_height));
221  // draw...
222  if (!ids_aruco_cache[pair.first].empty())
223  cv::aruco::drawDetectedMarkers(img_temp, corners_cache[pair.first], ids_aruco_cache[pair.first]);
224  if (!rejects_cache[pair.first].empty())
225  cv::aruco::drawDetectedMarkers(img_temp, rejects_cache[pair.first], cv::noArray(), cv::Scalar(100, 0, 255));
226  // Draw what camera this is
227  auto txtpt = (is_small) ? cv::Point(10, 30) : cv::Point(30, 60);
228  if (overlay == "") {
229  cv::putText(img_temp, "CAM:" + std::to_string((int)pair.first), txtpt, cv::FONT_HERSHEY_COMPLEX_SMALL, (is_small) ? 1.5 : 3.0,
230  cv::Scalar(0, 255, 0), 3);
231  } else {
232  cv::putText(img_temp, overlay, txtpt, cv::FONT_HERSHEY_COMPLEX_SMALL, (is_small) ? 1.5 : 3.0, cv::Scalar(0, 0, 255), 3);
233  }
234  // Overlay the mask
235  cv::Mat mask = cv::Mat::zeros(img_mask_last_cache[pair.first].rows, img_mask_last_cache[pair.first].cols, CV_8UC3);
236  mask.setTo(cv::Scalar(0, 0, 255), img_mask_last_cache[pair.first]);
237  cv::addWeighted(mask, 0.1, img_temp, 1.0, 0.0, img_temp);
238  // Replace the output image
239  img_temp.copyTo(img_out(cv::Rect(max_width * index_cam, 0, img_last_cache[pair.first].cols, img_last_cache[pair.first].rows)));
240  index_cam++;
241  }
242 }
243 
244 #endif
FeatureDatabase.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
ov_core::TrackAruco::do_downsizing
bool do_downsizing
Definition: TrackAruco.h:107
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::rT3
boost::posix_time::ptime rT3
Definition: TrackBase.h:195
ov_core::TrackAruco::feed_new_camera
void feed_new_camera(const CameraData &message) override
Process a new image.
Definition: TrackAruco.cpp:31
ov_core::CameraData::images
std::vector< cv::Mat > images
Raw image we have collected for each camera.
Definition: sensor_data.h:64
Feature.h
ov_core::CameraData
Struct for a collection of camera measurements.
Definition: sensor_data.h:55
PRINT_ERROR
#define PRINT_ERROR(x...)
Definition: print.h:100
PRINT_ALL
#define PRINT_ALL(x...)
Definition: print.h:96
ov_core::CameraData::sensor_ids
std::vector< int > sensor_ids
Camera ids for each of the images collected.
Definition: sensor_data.h:61
ov_core::TrackBase::histogram_method
HistogramMethod histogram_method
What histogram equalization method we should pre-process images with?
Definition: TrackBase.h:171
ov_core::CameraData::masks
std::vector< cv::Mat > masks
Tracking masks for each camera we have.
Definition: sensor_data.h:67
ov_core::TrackAruco::max_tag_id
int max_tag_id
Definition: TrackAruco.h:104
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
ov_core::LambdaBody
Definition: opencv_lambda_body.h:37
CamBase.h
ov_core::TrackBase::rT2
boost::posix_time::ptime rT2
Definition: TrackBase.h:195
RED
#define RED
Definition: colors.h:27
ov_core::TrackBase::rT1
boost::posix_time::ptime rT1
Definition: TrackBase.h:195
RESET
#define RESET
Definition: colors.h:25
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::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
opencv_lambda_body.h
TrackAruco.h


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:46