VioManager.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 "VioManager.h"
23 
24 #include "feat/Feature.h"
25 #include "feat/FeatureDatabase.h"
27 #include "track/TrackAruco.h"
28 #include "track/TrackDescriptor.h"
29 #include "track/TrackKLT.h"
30 #include "track/TrackSIM.h"
31 #include "types/Landmark.h"
34 #include "utils/print.h"
35 #include "utils/sensor_data.h"
36 
38 
39 #include "state/Propagator.h"
40 #include "state/State.h"
41 #include "state/StateHelper.h"
42 #include "update/UpdaterMSCKF.h"
43 #include "update/UpdaterSLAM.h"
45 
46 using namespace ov_core;
47 using namespace ov_type;
48 using namespace ov_msckf;
49 
50 VioManager::VioManager(VioManagerOptions &params_) : thread_init_running(false), thread_init_success(false) {
51 
52  // Nice startup message
53  PRINT_DEBUG("=======================================\n");
54  PRINT_DEBUG("OPENVINS ON-MANIFOLD EKF IS STARTING\n");
55  PRINT_DEBUG("=======================================\n");
56 
57  // Nice debug
58  this->params = params_;
63 
64  // This will globally set the thread count we will use
65  // -1 will reset to the system default threading (usually the num of cores)
66  cv::setNumThreads(params.num_opencv_threads);
67  cv::setRNGSeed(0);
68 
69  // Create the state!!
70  state = std::make_shared<State>(params.state_options);
71 
72  // Set the IMU intrinsics
73  state->_calib_imu_dw->set_value(params.vec_dw);
74  state->_calib_imu_dw->set_fej(params.vec_dw);
75  state->_calib_imu_da->set_value(params.vec_da);
76  state->_calib_imu_da->set_fej(params.vec_da);
77  state->_calib_imu_tg->set_value(params.vec_tg);
78  state->_calib_imu_tg->set_fej(params.vec_tg);
79  state->_calib_imu_GYROtoIMU->set_value(params.q_GYROtoIMU);
80  state->_calib_imu_GYROtoIMU->set_fej(params.q_GYROtoIMU);
81  state->_calib_imu_ACCtoIMU->set_value(params.q_ACCtoIMU);
82  state->_calib_imu_ACCtoIMU->set_fej(params.q_ACCtoIMU);
83 
84  // Timeoffset from camera to IMU
85  Eigen::VectorXd temp_camimu_dt;
86  temp_camimu_dt.resize(1);
87  temp_camimu_dt(0) = params.calib_camimu_dt;
88  state->_calib_dt_CAMtoIMU->set_value(temp_camimu_dt);
89  state->_calib_dt_CAMtoIMU->set_fej(temp_camimu_dt);
90 
91  // Loop through and load each of the cameras
92  state->_cam_intrinsics_cameras = params.camera_intrinsics;
93  for (int i = 0; i < state->_options.num_cameras; i++) {
94  state->_cam_intrinsics.at(i)->set_value(params.camera_intrinsics.at(i)->get_value());
95  state->_cam_intrinsics.at(i)->set_fej(params.camera_intrinsics.at(i)->get_value());
96  state->_calib_IMUtoCAM.at(i)->set_value(params.camera_extrinsics.at(i));
97  state->_calib_IMUtoCAM.at(i)->set_fej(params.camera_extrinsics.at(i));
98  }
99 
100  //===================================================================================
101  //===================================================================================
102  //===================================================================================
103 
104  // If we are recording statistics, then open our file
106  // If the file exists, then delete it
107  if (boost::filesystem::exists(params.record_timing_filepath)) {
108  boost::filesystem::remove(params.record_timing_filepath);
109  PRINT_INFO(YELLOW "[STATS]: found old file found, deleted...\n" RESET);
110  }
111  // Create the directory that we will open the file in
112  boost::filesystem::path p(params.record_timing_filepath);
113  boost::filesystem::create_directories(p.parent_path());
114  // Open our statistics file!
115  of_statistics.open(params.record_timing_filepath, std::ofstream::out | std::ofstream::app);
116  // Write the header information into it
117  of_statistics << "# timestamp (sec),tracking,propagation,msckf update,";
118  if (state->_options.max_slam_features > 0) {
119  of_statistics << "slam update,slam delayed,";
120  }
121  of_statistics << "re-tri & marg,total" << std::endl;
122  }
123 
124  //===================================================================================
125  //===================================================================================
126  //===================================================================================
127 
128  // Let's make a feature extractor
129  // NOTE: after we initialize we will increase the total number of feature tracks
130  // NOTE: we will split the total number of features over all cameras uniformly
131  int init_max_features = std::floor((double)params.init_options.init_max_features / (double)params.state_options.num_cameras);
132  if (params.use_klt) {
133  trackFEATS = std::shared_ptr<TrackBase>(new TrackKLT(state->_cam_intrinsics_cameras, init_max_features,
134  state->_options.max_aruco_features, params.use_stereo, params.histogram_method,
136  } else {
137  trackFEATS = std::shared_ptr<TrackBase>(new TrackDescriptor(
138  state->_cam_intrinsics_cameras, init_max_features, state->_options.max_aruco_features, params.use_stereo, params.histogram_method,
140  }
141 
142  // Initialize our aruco tag extractor
143  if (params.use_aruco) {
144  trackARUCO = std::shared_ptr<TrackBase>(new TrackAruco(state->_cam_intrinsics_cameras, state->_options.max_aruco_features,
146  }
147 
148  // Initialize our state propagator
149  propagator = std::make_shared<Propagator>(params.imu_noises, params.gravity_mag);
150 
151  // Our state initialize
152  initializer = std::make_shared<ov_init::InertialInitializer>(params.init_options, trackFEATS->get_feature_database());
153 
154  // Make the updater!
155  updaterMSCKF = std::make_shared<UpdaterMSCKF>(params.msckf_options, params.featinit_options);
156  updaterSLAM = std::make_shared<UpdaterSLAM>(params.slam_options, params.aruco_options, params.featinit_options);
157 
158  // If we are using zero velocity updates, then create the updater
159  if (params.try_zupt) {
160  updaterZUPT = std::make_shared<UpdaterZeroVelocity>(params.zupt_options, params.imu_noises, trackFEATS->get_feature_database(),
163  }
164 }
165 
167 
168  // The oldest time we need IMU with is the last clone
169  // We shouldn't really need the whole window, but if we go backwards in time we will
170  double oldest_time = state->margtimestep();
171  if (oldest_time > state->_timestamp) {
172  oldest_time = -1;
173  }
174  if (!is_initialized_vio) {
175  oldest_time = message.timestamp - params.init_options.init_window_time + state->_calib_dt_CAMtoIMU->value()(0) - 0.10;
176  }
177  propagator->feed_imu(message, oldest_time);
178 
179  // Push back to our initializer
180  if (!is_initialized_vio) {
181  initializer->feed_imu(message, oldest_time);
182  }
183 
184  // Push back to the zero velocity updater if it is enabled
185  // No need to push back if we are just doing the zv-update at the begining and we have moved
187  updaterZUPT->feed_imu(message, oldest_time);
188  }
189 }
190 
191 void VioManager::feed_measurement_simulation(double timestamp, const std::vector<int> &camids,
192  const std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats) {
193 
194  // Start timing
195  rT1 = boost::posix_time::microsec_clock::local_time();
196 
197  // Check if we actually have a simulated tracker
198  // If not, recreate and re-cast the tracker to our simulation tracker
199  std::shared_ptr<TrackSIM> trackSIM = std::dynamic_pointer_cast<TrackSIM>(trackFEATS);
200  if (trackSIM == nullptr) {
201  // Replace with the simulated tracker
202  trackSIM = std::make_shared<TrackSIM>(state->_cam_intrinsics_cameras, state->_options.max_aruco_features);
203  trackFEATS = trackSIM;
204  // Need to also replace it in init and zv-upt since it points to the trackFEATS db pointer
205  initializer = std::make_shared<ov_init::InertialInitializer>(params.init_options, trackFEATS->get_feature_database());
206  if (params.try_zupt) {
207  updaterZUPT = std::make_shared<UpdaterZeroVelocity>(params.zupt_options, params.imu_noises, trackFEATS->get_feature_database(),
210  }
211  PRINT_WARNING(RED "[SIM]: casting our tracker to a TrackSIM object!\n" RESET);
212  }
213 
214  // Feed our simulation tracker
215  trackSIM->feed_measurement_simulation(timestamp, camids, feats);
216  rT2 = boost::posix_time::microsec_clock::local_time();
217 
218  // Check if we should do zero-velocity, if so update the state with it
219  // Note that in the case that we only use in the beginning initialization phase
220  // If we have since moved, then we should never try to do a zero velocity update!
222  // If the same state time, use the previous timestep decision
223  if (state->_timestamp != timestamp) {
224  did_zupt_update = updaterZUPT->try_update(state, timestamp);
225  }
226  if (did_zupt_update) {
227  assert(state->_timestamp == timestamp);
228  propagator->clean_old_imu_measurements(timestamp + state->_calib_dt_CAMtoIMU->value()(0) - 0.10);
229  updaterZUPT->clean_old_imu_measurements(timestamp + state->_calib_dt_CAMtoIMU->value()(0) - 0.10);
230  propagator->invalidate_cache();
231  return;
232  }
233  }
234 
235  // If we do not have VIO initialization, then return an error
236  if (!is_initialized_vio) {
237  PRINT_ERROR(RED "[SIM]: your vio system should already be initialized before simulating features!!!\n" RESET);
238  PRINT_ERROR(RED "[SIM]: initialize your system first before calling feed_measurement_simulation()!!!!\n" RESET);
239  std::exit(EXIT_FAILURE);
240  }
241 
242  // Call on our propagate and update function
243  // Simulation is either all sync, or single camera...
244  ov_core::CameraData message;
245  message.timestamp = timestamp;
246  for (auto const &camid : camids) {
247  int width = state->_cam_intrinsics_cameras.at(camid)->w();
248  int height = state->_cam_intrinsics_cameras.at(camid)->h();
249  message.sensor_ids.push_back(camid);
250  message.images.push_back(cv::Mat::zeros(cv::Size(width, height), CV_8UC1));
251  message.masks.push_back(cv::Mat::zeros(cv::Size(width, height), CV_8UC1));
252  }
254 }
255 
257 
258  // Start timing
259  rT1 = boost::posix_time::microsec_clock::local_time();
260 
261  // Assert we have valid measurement data and ids
262  assert(!message_const.sensor_ids.empty());
263  assert(message_const.sensor_ids.size() == message_const.images.size());
264  for (size_t i = 0; i < message_const.sensor_ids.size() - 1; i++) {
265  assert(message_const.sensor_ids.at(i) != message_const.sensor_ids.at(i + 1));
266  }
267 
268  // Downsample if we are downsampling
269  ov_core::CameraData message = message_const;
270  for (size_t i = 0; i < message.sensor_ids.size() && params.downsample_cameras; i++) {
271  cv::Mat img = message.images.at(i);
272  cv::Mat mask = message.masks.at(i);
273  cv::Mat img_temp, mask_temp;
274  cv::pyrDown(img, img_temp, cv::Size(img.cols / 2.0, img.rows / 2.0));
275  message.images.at(i) = img_temp;
276  cv::pyrDown(mask, mask_temp, cv::Size(mask.cols / 2.0, mask.rows / 2.0));
277  message.masks.at(i) = mask_temp;
278  }
279 
280  // Perform our feature tracking!
281  trackFEATS->feed_new_camera(message);
282 
283  // If the aruco tracker is available, the also pass to it
284  // NOTE: binocular tracking for aruco doesn't make sense as we by default have the ids
285  // NOTE: thus we just call the stereo tracking if we are doing binocular!
286  if (is_initialized_vio && trackARUCO != nullptr) {
287  trackARUCO->feed_new_camera(message);
288  }
289  rT2 = boost::posix_time::microsec_clock::local_time();
290 
291  // Check if we should do zero-velocity, if so update the state with it
292  // Note that in the case that we only use in the beginning initialization phase
293  // If we have since moved, then we should never try to do a zero velocity update!
295  // If the same state time, use the previous timestep decision
296  if (state->_timestamp != message.timestamp) {
297  did_zupt_update = updaterZUPT->try_update(state, message.timestamp);
298  }
299  if (did_zupt_update) {
300  assert(state->_timestamp == message.timestamp);
301  propagator->clean_old_imu_measurements(message.timestamp + state->_calib_dt_CAMtoIMU->value()(0) - 0.10);
302  updaterZUPT->clean_old_imu_measurements(message.timestamp + state->_calib_dt_CAMtoIMU->value()(0) - 0.10);
303  propagator->invalidate_cache();
304  return;
305  }
306  }
307 
308  // If we do not have VIO initialization, then try to initialize
309  // TODO: Or if we are trying to reset the system, then do that here!
310  if (!is_initialized_vio) {
312  if (!is_initialized_vio) {
313  double time_track = (rT2 - rT1).total_microseconds() * 1e-6;
314  PRINT_DEBUG(BLUE "[TIME]: %.4f seconds for tracking\n" RESET, time_track);
315  return;
316  }
317  }
318 
319  // Call on our propagate and update function
321 }
322 
324 
325  //===================================================================================
326  // State propagation, and clone augmentation
327  //===================================================================================
328 
329  // Return if the camera measurement is out of order
330  if (state->_timestamp > message.timestamp) {
331  PRINT_WARNING(YELLOW "image received out of order, unable to do anything (prop dt = %3f)\n" RESET,
332  (message.timestamp - state->_timestamp));
333  return;
334  }
335 
336  // Propagate the state forward to the current update time
337  // Also augment it with a new clone!
338  // NOTE: if the state is already at the given time (can happen in sim)
339  // NOTE: then no need to prop since we already are at the desired timestep
340  if (state->_timestamp != message.timestamp) {
341  propagator->propagate_and_clone(state, message.timestamp);
342  }
343  rT3 = boost::posix_time::microsec_clock::local_time();
344 
345  // If we have not reached max clones, we should just return...
346  // This isn't super ideal, but it keeps the logic after this easier...
347  // We can start processing things when we have at least 5 clones since we can start triangulating things...
348  if ((int)state->_clones_IMU.size() < std::min(state->_options.max_clone_size, 5)) {
349  PRINT_DEBUG("waiting for enough clone states (%d of %d)....\n", (int)state->_clones_IMU.size(),
350  std::min(state->_options.max_clone_size, 5));
351  return;
352  }
353 
354  // Return if we where unable to propagate
355  if (state->_timestamp != message.timestamp) {
356  PRINT_WARNING(RED "[PROP]: Propagator unable to propagate the state forward in time!\n" RESET);
357  PRINT_WARNING(RED "[PROP]: It has been %.3f since last time we propagated\n" RESET, message.timestamp - state->_timestamp);
358  return;
359  }
360  has_moved_since_zupt = true;
361 
362  //===================================================================================
363  // MSCKF features and KLT tracks that are SLAM features
364  //===================================================================================
365 
366  // Now, lets get all features that should be used for an update that are lost in the newest frame
367  // We explicitly request features that have not been deleted (used) in another update step
368  std::vector<std::shared_ptr<Feature>> feats_lost, feats_marg, feats_slam;
369  feats_lost = trackFEATS->get_feature_database()->features_not_containing_newer(state->_timestamp, false, true);
370 
371  // Don't need to get the oldest features until we reach our max number of clones
372  if ((int)state->_clones_IMU.size() > state->_options.max_clone_size || (int)state->_clones_IMU.size() > 5) {
373  feats_marg = trackFEATS->get_feature_database()->features_containing(state->margtimestep(), false, true);
374  if (trackARUCO != nullptr && message.timestamp - startup_time >= params.dt_slam_delay) {
375  feats_slam = trackARUCO->get_feature_database()->features_containing(state->margtimestep(), false, true);
376  }
377  }
378 
379  // Remove any lost features that were from other image streams
380  // E.g: if we are cam1 and cam0 has not processed yet, we don't want to try to use those in the update yet
381  // E.g: thus we wait until cam0 process its newest image to remove features which were seen from that camera
382  auto it1 = feats_lost.begin();
383  while (it1 != feats_lost.end()) {
384  bool found_current_message_camid = false;
385  for (const auto &camuvpair : (*it1)->uvs) {
386  if (std::find(message.sensor_ids.begin(), message.sensor_ids.end(), camuvpair.first) != message.sensor_ids.end()) {
387  found_current_message_camid = true;
388  break;
389  }
390  }
391  if (found_current_message_camid) {
392  it1++;
393  } else {
394  it1 = feats_lost.erase(it1);
395  }
396  }
397 
398  // We also need to make sure that the max tracks does not contain any lost features
399  // This could happen if the feature was lost in the last frame, but has a measurement at the marg timestep
400  it1 = feats_lost.begin();
401  while (it1 != feats_lost.end()) {
402  if (std::find(feats_marg.begin(), feats_marg.end(), (*it1)) != feats_marg.end()) {
403  // PRINT_WARNING(YELLOW "FOUND FEATURE THAT WAS IN BOTH feats_lost and feats_marg!!!!!!\n" RESET);
404  it1 = feats_lost.erase(it1);
405  } else {
406  it1++;
407  }
408  }
409 
410  // Find tracks that have reached max length, these can be made into SLAM features
411  std::vector<std::shared_ptr<Feature>> feats_maxtracks;
412  auto it2 = feats_marg.begin();
413  while (it2 != feats_marg.end()) {
414  // See if any of our camera's reached max track
415  bool reached_max = false;
416  for (const auto &cams : (*it2)->timestamps) {
417  if ((int)cams.second.size() > state->_options.max_clone_size) {
418  reached_max = true;
419  break;
420  }
421  }
422  // If max track, then add it to our possible slam feature list
423  if (reached_max) {
424  feats_maxtracks.push_back(*it2);
425  it2 = feats_marg.erase(it2);
426  } else {
427  it2++;
428  }
429  }
430 
431  // Count how many aruco tags we have in our state
432  int curr_aruco_tags = 0;
433  auto it0 = state->_features_SLAM.begin();
434  while (it0 != state->_features_SLAM.end()) {
435  if ((int)(*it0).second->_featid <= 4 * state->_options.max_aruco_features)
436  curr_aruco_tags++;
437  it0++;
438  }
439 
440  // Append a new SLAM feature if we have the room to do so
441  // Also check that we have waited our delay amount (normally prevents bad first set of slam points)
442  if (state->_options.max_slam_features > 0 && message.timestamp - startup_time >= params.dt_slam_delay &&
443  (int)state->_features_SLAM.size() < state->_options.max_slam_features + curr_aruco_tags) {
444  // Get the total amount to add, then the max amount that we can add given our marginalize feature array
445  int amount_to_add = (state->_options.max_slam_features + curr_aruco_tags) - (int)state->_features_SLAM.size();
446  int valid_amount = (amount_to_add > (int)feats_maxtracks.size()) ? (int)feats_maxtracks.size() : amount_to_add;
447  // If we have at least 1 that we can add, lets add it!
448  // Note: we remove them from the feat_marg array since we don't want to reuse information...
449  if (valid_amount > 0) {
450  feats_slam.insert(feats_slam.end(), feats_maxtracks.end() - valid_amount, feats_maxtracks.end());
451  feats_maxtracks.erase(feats_maxtracks.end() - valid_amount, feats_maxtracks.end());
452  }
453  }
454 
455  // Loop through current SLAM features, we have tracks of them, grab them for this update!
456  // NOTE: if we have a slam feature that has lost tracking, then we should marginalize it out
457  // NOTE: we only enforce this if the current camera message is where the feature was seen from
458  // NOTE: if you do not use FEJ, these types of slam features *degrade* the estimator performance....
459  // NOTE: we will also marginalize SLAM features if they have failed their update a couple times in a row
460  for (std::pair<const size_t, std::shared_ptr<Landmark>> &landmark : state->_features_SLAM) {
461  if (trackARUCO != nullptr) {
462  std::shared_ptr<Feature> feat1 = trackARUCO->get_feature_database()->get_feature(landmark.second->_featid);
463  if (feat1 != nullptr)
464  feats_slam.push_back(feat1);
465  }
466  std::shared_ptr<Feature> feat2 = trackFEATS->get_feature_database()->get_feature(landmark.second->_featid);
467  if (feat2 != nullptr)
468  feats_slam.push_back(feat2);
469  assert(landmark.second->_unique_camera_id != -1);
470  bool current_unique_cam =
471  std::find(message.sensor_ids.begin(), message.sensor_ids.end(), landmark.second->_unique_camera_id) != message.sensor_ids.end();
472  if (feat2 == nullptr && current_unique_cam)
473  landmark.second->should_marg = true;
474  if (landmark.second->update_fail_count > 1)
475  landmark.second->should_marg = true;
476  }
477 
478  // Lets marginalize out all old SLAM features here
479  // These are ones that where not successfully tracked into the current frame
480  // We do *NOT* marginalize out our aruco tags landmarks
482 
483  // Separate our SLAM features into new ones, and old ones
484  std::vector<std::shared_ptr<Feature>> feats_slam_DELAYED, feats_slam_UPDATE;
485  for (size_t i = 0; i < feats_slam.size(); i++) {
486  if (state->_features_SLAM.find(feats_slam.at(i)->featid) != state->_features_SLAM.end()) {
487  feats_slam_UPDATE.push_back(feats_slam.at(i));
488  // PRINT_DEBUG("[UPDATE-SLAM]: found old feature %d (%d
489  // measurements)\n",(int)feats_slam.at(i)->featid,(int)feats_slam.at(i)->timestamps_left.size());
490  } else {
491  feats_slam_DELAYED.push_back(feats_slam.at(i));
492  // PRINT_DEBUG("[UPDATE-SLAM]: new feature ready %d (%d
493  // measurements)\n",(int)feats_slam.at(i)->featid,(int)feats_slam.at(i)->timestamps_left.size());
494  }
495  }
496 
497  // Concatenate our MSCKF feature arrays (i.e., ones not being used for slam updates)
498  std::vector<std::shared_ptr<Feature>> featsup_MSCKF = feats_lost;
499  featsup_MSCKF.insert(featsup_MSCKF.end(), feats_marg.begin(), feats_marg.end());
500  featsup_MSCKF.insert(featsup_MSCKF.end(), feats_maxtracks.begin(), feats_maxtracks.end());
501 
502  //===================================================================================
503  // Now that we have a list of features, lets do the EKF update for MSCKF and SLAM!
504  //===================================================================================
505 
506  // Sort based on track length
507  // TODO: we should have better selection logic here (i.e. even feature distribution in the FOV etc..)
508  // TODO: right now features that are "lost" are at the front of this vector, while ones at the end are long-tracks
509  auto compare_feat = [](const std::shared_ptr<Feature> &a, const std::shared_ptr<Feature> &b) -> bool {
510  size_t asize = 0;
511  size_t bsize = 0;
512  for (const auto &pair : a->timestamps)
513  asize += pair.second.size();
514  for (const auto &pair : b->timestamps)
515  bsize += pair.second.size();
516  return asize < bsize;
517  };
518  std::sort(featsup_MSCKF.begin(), featsup_MSCKF.end(), compare_feat);
519 
520  // Pass them to our MSCKF updater
521  // NOTE: if we have more then the max, we select the "best" ones (i.e. max tracks) for this update
522  // NOTE: this should only really be used if you want to track a lot of features, or have limited computational resources
523  if ((int)featsup_MSCKF.size() > state->_options.max_msckf_in_update)
524  featsup_MSCKF.erase(featsup_MSCKF.begin(), featsup_MSCKF.end() - state->_options.max_msckf_in_update);
525  updaterMSCKF->update(state, featsup_MSCKF);
526  propagator->invalidate_cache();
527  rT4 = boost::posix_time::microsec_clock::local_time();
528 
529  // Perform SLAM delay init and update
530  // NOTE: that we provide the option here to do a *sequential* update
531  // NOTE: this will be a lot faster but won't be as accurate.
532  std::vector<std::shared_ptr<Feature>> feats_slam_UPDATE_TEMP;
533  while (!feats_slam_UPDATE.empty()) {
534  // Get sub vector of the features we will update with
535  std::vector<std::shared_ptr<Feature>> featsup_TEMP;
536  featsup_TEMP.insert(featsup_TEMP.begin(), feats_slam_UPDATE.begin(),
537  feats_slam_UPDATE.begin() + std::min(state->_options.max_slam_in_update, (int)feats_slam_UPDATE.size()));
538  feats_slam_UPDATE.erase(feats_slam_UPDATE.begin(),
539  feats_slam_UPDATE.begin() + std::min(state->_options.max_slam_in_update, (int)feats_slam_UPDATE.size()));
540  // Do the update
541  updaterSLAM->update(state, featsup_TEMP);
542  feats_slam_UPDATE_TEMP.insert(feats_slam_UPDATE_TEMP.end(), featsup_TEMP.begin(), featsup_TEMP.end());
543  propagator->invalidate_cache();
544  }
545  feats_slam_UPDATE = feats_slam_UPDATE_TEMP;
546  rT5 = boost::posix_time::microsec_clock::local_time();
547  updaterSLAM->delayed_init(state, feats_slam_DELAYED);
548  rT6 = boost::posix_time::microsec_clock::local_time();
549 
550  //===================================================================================
551  // Update our visualization feature set, and clean up the old features
552  //===================================================================================
553 
554  // Re-triangulate all current tracks in the current frame
555  if (message.sensor_ids.at(0) == 0) {
556 
557  // Re-triangulate features
559 
560  // Clear the MSCKF features only on the base camera
561  // Thus we should be able to visualize the other unique camera stream
562  // MSCKF features as they will also be appended to the vector
563  good_features_MSCKF.clear();
564  }
565 
566  // Save all the MSCKF features used in the update
567  for (auto const &feat : featsup_MSCKF) {
568  good_features_MSCKF.push_back(feat->p_FinG);
569  feat->to_delete = true;
570  }
571 
572  //===================================================================================
573  // Cleanup, marginalize out what we don't need any more...
574  //===================================================================================
575 
576  // Remove features that where used for the update from our extractors at the last timestep
577  // This allows for measurements to be used in the future if they failed to be used this time
578  // Note we need to do this before we feed a new image, as we want all new measurements to NOT be deleted
579  trackFEATS->get_feature_database()->cleanup();
580  if (trackARUCO != nullptr) {
581  trackARUCO->get_feature_database()->cleanup();
582  }
583 
584  // First do anchor change if we are about to lose an anchor pose
585  updaterSLAM->change_anchors(state);
586 
587  // Cleanup any features older than the marginalization time
588  if ((int)state->_clones_IMU.size() > state->_options.max_clone_size) {
589  trackFEATS->get_feature_database()->cleanup_measurements(state->margtimestep());
590  if (trackARUCO != nullptr) {
591  trackARUCO->get_feature_database()->cleanup_measurements(state->margtimestep());
592  }
593  }
594 
595  // Finally marginalize the oldest clone if needed
597  rT7 = boost::posix_time::microsec_clock::local_time();
598 
599  //===================================================================================
600  // Debug info, and stats tracking
601  //===================================================================================
602 
603  // Get timing statitics information
604  double time_track = (rT2 - rT1).total_microseconds() * 1e-6;
605  double time_prop = (rT3 - rT2).total_microseconds() * 1e-6;
606  double time_msckf = (rT4 - rT3).total_microseconds() * 1e-6;
607  double time_slam_update = (rT5 - rT4).total_microseconds() * 1e-6;
608  double time_slam_delay = (rT6 - rT5).total_microseconds() * 1e-6;
609  double time_marg = (rT7 - rT6).total_microseconds() * 1e-6;
610  double time_total = (rT7 - rT1).total_microseconds() * 1e-6;
611 
612  // Timing information
613  PRINT_DEBUG(BLUE "[TIME]: %.4f seconds for tracking\n" RESET, time_track);
614  PRINT_DEBUG(BLUE "[TIME]: %.4f seconds for propagation\n" RESET, time_prop);
615  PRINT_DEBUG(BLUE "[TIME]: %.4f seconds for MSCKF update (%d feats)\n" RESET, time_msckf, (int)featsup_MSCKF.size());
616  if (state->_options.max_slam_features > 0) {
617  PRINT_DEBUG(BLUE "[TIME]: %.4f seconds for SLAM update (%d feats)\n" RESET, time_slam_update, (int)state->_features_SLAM.size());
618  PRINT_DEBUG(BLUE "[TIME]: %.4f seconds for SLAM delayed init (%d feats)\n" RESET, time_slam_delay, (int)feats_slam_DELAYED.size());
619  }
620  PRINT_DEBUG(BLUE "[TIME]: %.4f seconds for re-tri & marg (%d clones in state)\n" RESET, time_marg, (int)state->_clones_IMU.size());
621 
622  std::stringstream ss;
623  ss << "[TIME]: " << std::setprecision(4) << time_total << " seconds for total (camera";
624  for (const auto &id : message.sensor_ids) {
625  ss << " " << id;
626  }
627  ss << ")" << std::endl;
628  PRINT_DEBUG(BLUE "%s" RESET, ss.str().c_str());
629 
630  // Finally if we are saving stats to file, lets save it to file
632  // We want to publish in the IMU clock frame
633  // The timestamp in the state will be the last camera time
634  double t_ItoC = state->_calib_dt_CAMtoIMU->value()(0);
635  double timestamp_inI = state->_timestamp + t_ItoC;
636  // Append to the file
637  of_statistics << std::fixed << std::setprecision(15) << timestamp_inI << "," << std::fixed << std::setprecision(5) << time_track << ","
638  << time_prop << "," << time_msckf << ",";
639  if (state->_options.max_slam_features > 0) {
640  of_statistics << time_slam_update << "," << time_slam_delay << ",";
641  }
642  of_statistics << time_marg << "," << time_total << std::endl;
643  of_statistics.flush();
644  }
645 
646  // Update our distance traveled
647  if (timelastupdate != -1 && state->_clones_IMU.find(timelastupdate) != state->_clones_IMU.end()) {
648  Eigen::Matrix<double, 3, 1> dx = state->_imu->pos() - state->_clones_IMU.at(timelastupdate)->pos();
649  distance += dx.norm();
650  }
651  timelastupdate = message.timestamp;
652 
653  // Debug, print our current state
654  PRINT_INFO("q_GtoI = %.3f,%.3f,%.3f,%.3f | p_IinG = %.3f,%.3f,%.3f | dist = %.2f (meters)\n", state->_imu->quat()(0),
655  state->_imu->quat()(1), state->_imu->quat()(2), state->_imu->quat()(3), state->_imu->pos()(0), state->_imu->pos()(1),
656  state->_imu->pos()(2), distance);
657  PRINT_INFO("bg = %.4f,%.4f,%.4f | ba = %.4f,%.4f,%.4f\n", state->_imu->bias_g()(0), state->_imu->bias_g()(1), state->_imu->bias_g()(2),
658  state->_imu->bias_a()(0), state->_imu->bias_a()(1), state->_imu->bias_a()(2));
659 
660  // Debug for camera imu offset
661  if (state->_options.do_calib_camera_timeoffset) {
662  PRINT_INFO("camera-imu timeoffset = %.5f\n", state->_calib_dt_CAMtoIMU->value()(0));
663  }
664 
665  // Debug for camera intrinsics
666  if (state->_options.do_calib_camera_intrinsics) {
667  for (int i = 0; i < state->_options.num_cameras; i++) {
668  std::shared_ptr<Vec> calib = state->_cam_intrinsics.at(i);
669  PRINT_INFO("cam%d intrinsics = %.3f,%.3f,%.3f,%.3f | %.3f,%.3f,%.3f,%.3f\n", (int)i, calib->value()(0), calib->value()(1),
670  calib->value()(2), calib->value()(3), calib->value()(4), calib->value()(5), calib->value()(6), calib->value()(7));
671  }
672  }
673 
674  // Debug for camera extrinsics
675  if (state->_options.do_calib_camera_pose) {
676  for (int i = 0; i < state->_options.num_cameras; i++) {
677  std::shared_ptr<PoseJPL> calib = state->_calib_IMUtoCAM.at(i);
678  PRINT_INFO("cam%d extrinsics = %.3f,%.3f,%.3f,%.3f | %.3f,%.3f,%.3f\n", (int)i, calib->quat()(0), calib->quat()(1), calib->quat()(2),
679  calib->quat()(3), calib->pos()(0), calib->pos()(1), calib->pos()(2));
680  }
681  }
682 
683  // Debug for imu intrinsics
684  if (state->_options.do_calib_imu_intrinsics && state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
685  PRINT_INFO("q_GYROtoI = %.3f,%.3f,%.3f,%.3f\n", state->_calib_imu_GYROtoIMU->value()(0), state->_calib_imu_GYROtoIMU->value()(1),
686  state->_calib_imu_GYROtoIMU->value()(2), state->_calib_imu_GYROtoIMU->value()(3));
687  }
688  if (state->_options.do_calib_imu_intrinsics && state->_options.imu_model == StateOptions::ImuModel::RPNG) {
689  PRINT_INFO("q_ACCtoI = %.3f,%.3f,%.3f,%.3f\n", state->_calib_imu_ACCtoIMU->value()(0), state->_calib_imu_ACCtoIMU->value()(1),
690  state->_calib_imu_ACCtoIMU->value()(2), state->_calib_imu_ACCtoIMU->value()(3));
691  }
692  if (state->_options.do_calib_imu_intrinsics && state->_options.imu_model == StateOptions::ImuModel::KALIBR) {
693  PRINT_INFO("Dw = | %.4f,%.4f,%.4f | %.4f,%.4f | %.4f |\n", state->_calib_imu_dw->value()(0), state->_calib_imu_dw->value()(1),
694  state->_calib_imu_dw->value()(2), state->_calib_imu_dw->value()(3), state->_calib_imu_dw->value()(4),
695  state->_calib_imu_dw->value()(5));
696  PRINT_INFO("Da = | %.4f,%.4f,%.4f | %.4f,%.4f | %.4f |\n", state->_calib_imu_da->value()(0), state->_calib_imu_da->value()(1),
697  state->_calib_imu_da->value()(2), state->_calib_imu_da->value()(3), state->_calib_imu_da->value()(4),
698  state->_calib_imu_da->value()(5));
699  }
700  if (state->_options.do_calib_imu_intrinsics && state->_options.imu_model == StateOptions::ImuModel::RPNG) {
701  PRINT_INFO("Dw = | %.4f | %.4f,%.4f | %.4f,%.4f,%.4f |\n", state->_calib_imu_dw->value()(0), state->_calib_imu_dw->value()(1),
702  state->_calib_imu_dw->value()(2), state->_calib_imu_dw->value()(3), state->_calib_imu_dw->value()(4),
703  state->_calib_imu_dw->value()(5));
704  PRINT_INFO("Da = | %.4f | %.4f,%.4f | %.4f,%.4f,%.4f |\n", state->_calib_imu_da->value()(0), state->_calib_imu_da->value()(1),
705  state->_calib_imu_da->value()(2), state->_calib_imu_da->value()(3), state->_calib_imu_da->value()(4),
706  state->_calib_imu_da->value()(5));
707  }
708  if (state->_options.do_calib_imu_intrinsics && state->_options.do_calib_imu_g_sensitivity) {
709  PRINT_INFO("Tg = | %.4f,%.4f,%.4f | %.4f,%.4f,%.4f | %.4f,%.4f,%.4f |\n", state->_calib_imu_tg->value()(0),
710  state->_calib_imu_tg->value()(1), state->_calib_imu_tg->value()(2), state->_calib_imu_tg->value()(3),
711  state->_calib_imu_tg->value()(4), state->_calib_imu_tg->value()(5), state->_calib_imu_tg->value()(6),
712  state->_calib_imu_tg->value()(7), state->_calib_imu_tg->value()(8));
713  }
714 }
Propagator.h
ov_msckf::VioManagerOptions::camera_extrinsics
std::map< size_t, Eigen::VectorXd > camera_extrinsics
Map between camid and camera extrinsics (q_ItoC, p_IinC).
Definition: VioManagerOptions.h:214
ov_msckf::VioManager::did_zupt_update
bool did_zupt_update
Definition: VioManager.h:229
ov_msckf::VioManagerOptions::min_px_dist
int min_px_dist
Will check after doing KLT track and remove any features closer than this.
Definition: VioManagerOptions.h:433
ov_msckf::VioManagerOptions::msckf_options
UpdaterOptions msckf_options
Update options for MSCKF features (pixel noise and chi2 multiplier)
Definition: VioManagerOptions.h:139
ov_msckf::VioManager::trackFEATS
std::shared_ptr< ov_core::TrackBase > trackFEATS
Our sparse feature tracker (klt or descriptor)
Definition: VioManager.h:189
ov_msckf::VioManager::has_moved_since_zupt
bool has_moved_since_zupt
Definition: VioManager.h:230
ov_msckf::VioManagerOptions::zupt_max_velocity
double zupt_max_velocity
Max velocity we will consider to try to do a zupt (i.e. if above this, don't do zupt)
Definition: VioManagerOptions.h:86
UpdaterSLAM.h
TrackSIM.h
ov_msckf::VioManagerOptions::use_stereo
bool use_stereo
If we should process two cameras are being stereo or binocular. If binocular, we do monocular feature...
Definition: VioManagerOptions.h:397
ov_core::TrackAruco
opencv_lambda_body.h
ov_core::CameraData::images
std::vector< cv::Mat > images
ov_msckf::VioManager::initializer
std::shared_ptr< ov_init::InertialInitializer > initializer
State initializer.
Definition: VioManager.h:195
LandmarkRepresentation.h
ov_msckf::VioManager::params
VioManagerOptions params
Manager parameters.
Definition: VioManager.h:180
ov_msckf::VioManagerOptions::dt_slam_delay
double dt_slam_delay
Delay, in seconds, that we should wait from init before we start estimating SLAM features.
Definition: VioManagerOptions.h:80
YELLOW
YELLOW
InertialInitializer.h
ov_msckf::VioManager::state
std::shared_ptr< State > state
Our master state object :D.
Definition: VioManager.h:183
ov_msckf::VioManagerOptions::camera_intrinsics
std::unordered_map< size_t, std::shared_ptr< ov_core::CamBase > > camera_intrinsics
Map between camid and camera intrinsics (fx, fy, cx, cy, d1...d4, cam_w, cam_h)
Definition: VioManagerOptions.h:211
PRINT_DEBUG
#define PRINT_DEBUG(x...)
ov_msckf::VioManagerOptions::histogram_method
ov_core::TrackBase::HistogramMethod histogram_method
What type of pre-processing histogram method should be applied to images.
Definition: VioManagerOptions.h:436
ov_msckf::VioManagerOptions::print_and_load_trackers
void print_and_load_trackers(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all parameters related to visual tracking This allows for visual ch...
Definition: VioManagerOptions.h:453
ov_msckf::VioManager::rT4
boost::posix_time::ptime rT4
Definition: VioManager.h:216
FeatureInitializer.h
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::VioManager::rT1
boost::posix_time::ptime rT1
Definition: VioManager.h:216
ov_msckf::VioManagerOptions::zupt_max_disparity
double zupt_max_disparity
Max disparity we will consider to try to do a zupt (i.e. if above this, don't do zupt)
Definition: VioManagerOptions.h:92
ov_msckf::VioManagerOptions::vec_dw
Eigen::Matrix< double, 6, 1 > vec_dw
Gyroscope IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse)
Definition: VioManagerOptions.h:193
ov_msckf::VioManager::updaterZUPT
std::shared_ptr< UpdaterZeroVelocity > updaterZUPT
Our zero velocity tracker.
Definition: VioManager.h:207
sensor_data.h
ov_msckf::VioManager::do_feature_propagate_update
void do_feature_propagate_update(const ov_core::CameraData &message)
This will do the propagation and feature updates to the state.
Definition: VioManager.cpp:323
ov_msckf::VioManager::feed_measurement_imu
void feed_measurement_imu(const ov_core::ImuData &message)
Feed function for inertial data.
Definition: VioManager.cpp:166
ov_msckf::VioManagerOptions::downsample_cameras
bool downsample_cameras
Will half the resolution all tracking image (aruco will be 1/4 instead of halved if dowsize_aruoc als...
Definition: VioManagerOptions.h:409
ov_init::InertialInitializerOptions::init_max_features
int init_max_features
ov_core::CameraData
ov_msckf::VioManagerOptions::fast_threshold
int fast_threshold
Fast extraction threshold.
Definition: VioManagerOptions.h:424
ov_msckf::StateHelper::marginalize_slam
static void marginalize_slam(std::shared_ptr< State > state)
Marginalize bad SLAM features.
Definition: StateHelper.cpp:631
ov_msckf::VioManager::rT3
boost::posix_time::ptime rT3
Definition: VioManager.h:216
PRINT_ERROR
#define PRINT_ERROR(x...)
ov_msckf::VioManager::rT5
boost::posix_time::ptime rT5
Definition: VioManager.h:216
ov_msckf::VioManager::good_features_MSCKF
std::vector< Eigen::Vector3d > good_features_MSCKF
Definition: VioManager.h:233
StateHelper.h
ov_msckf::VioManagerOptions::record_timing_information
bool record_timing_information
If we should record the timing performance to file.
Definition: VioManagerOptions.h:98
ov_init::InertialInitializerOptions::init_window_time
double init_window_time
ov_core::CameraData::sensor_ids
std::vector< int > sensor_ids
UpdaterZeroVelocity.h
ov_msckf::VioManagerOptions::grid_x
int grid_x
Number of grids we should split column-wise to do feature extraction in.
Definition: VioManagerOptions.h:427
ov_msckf::VioManagerOptions::slam_options
UpdaterOptions slam_options
Update options for SLAM features (pixel noise and chi2 multiplier)
Definition: VioManagerOptions.h:142
ov_core::CameraData::timestamp
double timestamp
ov_core::CameraData::masks
std::vector< cv::Mat > masks
ov_msckf::VioManagerOptions::try_zupt
bool try_zupt
If we should try to use zero velocity update.
Definition: VioManagerOptions.h:83
ov_msckf::VioManager::rT2
boost::posix_time::ptime rT2
Definition: VioManager.h:216
ov_msckf::VioManagerOptions::zupt_only_at_beginning
bool zupt_only_at_beginning
If we should only use the zupt at the very beginning static initialization phase.
Definition: VioManagerOptions.h:95
ov_msckf::VioManager::trackARUCO
std::shared_ptr< ov_core::TrackBase > trackARUCO
Our aruoc tracker.
Definition: VioManager.h:192
ov_msckf::VioManagerOptions::grid_y
int grid_y
Number of grids we should split row-wise to do feature extraction in.
Definition: VioManagerOptions.h:430
VioManager.h
ov_msckf::VioManagerOptions::zupt_noise_multiplier
double zupt_noise_multiplier
Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)
Definition: VioManagerOptions.h:89
ov_msckf::VioManagerOptions::aruco_options
UpdaterOptions aruco_options
Update options for ARUCO features (pixel noise and chi2 multiplier)
Definition: VioManagerOptions.h:145
ov_msckf::VioManager::feed_measurement_simulation
void feed_measurement_simulation(double timestamp, const std::vector< int > &camids, const std::vector< std::vector< std::pair< size_t, Eigen::VectorXf >>> &feats)
Feed function for a synchronized simulated cameras.
Definition: VioManager.cpp:191
BLUE
BLUE
ov_msckf::VioManager::startup_time
double startup_time
Definition: VioManager.h:223
ov_msckf::VioManager::track_image_and_update
void track_image_and_update(const ov_core::CameraData &message)
Given a new set of camera images, this will track them.
Definition: VioManager.cpp:256
ov_msckf::VioManagerOptions::featinit_options
ov_core::FeatureInitializerOptions featinit_options
Parameters used by our feature initialize / triangulator.
Definition: VioManagerOptions.h:445
ov_msckf::VioManagerOptions::use_aruco
bool use_aruco
If should extract aruco tags and estimate them.
Definition: VioManagerOptions.h:403
ov_msckf::VioManagerOptions::downsize_aruco
bool downsize_aruco
Will half the resolution of the aruco tag image (will be faster)
Definition: VioManagerOptions.h:406
ov_msckf::VioManager::is_initialized_vio
bool is_initialized_vio
Boolean if we are initialized or not.
Definition: VioManager.h:198
ov_msckf::StateHelper::marginalize_old_clone
static void marginalize_old_clone(std::shared_ptr< State > state)
Remove the oldest clone, if we have more then the max clone count!!
Definition: StateHelper.cpp:618
ov_msckf::VioManager::rT6
boost::posix_time::ptime rT6
Definition: VioManager.h:216
ov_core::ImuData
ov_msckf::VioManagerOptions::calib_camimu_dt
double calib_camimu_dt
Time offset between camera and IMU.
Definition: VioManagerOptions.h:208
ov_msckf::VioManager::of_statistics
std::ofstream of_statistics
Definition: VioManager.h:215
ov_msckf::VioManagerOptions::init_options
ov_init::InertialInitializerOptions init_options
Our state initialization options (e.g. window size, num features, if we should get the calibration)
Definition: VioManagerOptions.h:77
ov_msckf::VioManagerOptions::use_klt
bool use_klt
If we should use KLT tracking, or descriptor matcher.
Definition: VioManagerOptions.h:400
ov_msckf::VioManagerOptions::gravity_mag
double gravity_mag
Gravity magnitude in the global frame (i.e. should be 9.81 typically)
Definition: VioManagerOptions.h:190
TrackDescriptor.h
TrackAruco.h
ov_msckf::VioManagerOptions::num_opencv_threads
int num_opencv_threads
Threads our front-end should try to use (opencv uses this also)
Definition: VioManagerOptions.h:412
ov_msckf::VioManagerOptions::imu_noises
NoiseManager imu_noises
Continuous-time IMU noise (gyroscope and accelerometer)
Definition: VioManagerOptions.h:136
ov_msckf::VioManager::try_to_initialize
bool try_to_initialize(const ov_core::CameraData &message)
This function will try to initialize the state.
Definition: VioManagerHelper.cpp:78
ov_msckf::VioManagerOptions::q_ACCtoIMU
Eigen::Matrix< double, 4, 1 > q_ACCtoIMU
Rotation from gyroscope frame to the "IMU" accelerometer frame.
Definition: VioManagerOptions.h:202
print.h
TrackKLT.h
ov_msckf::VioManagerOptions::vec_tg
Eigen::Matrix< double, 9, 1 > vec_tg
Gyroscope gravity sensitivity (scale imperfection and axis misalignment, column-wise)
Definition: VioManagerOptions.h:199
Landmark.h
PRINT_INFO
#define PRINT_INFO(x...)
ov_msckf::VioManagerOptions::q_GYROtoIMU
Eigen::Matrix< double, 4, 1 > q_GYROtoIMU
Rotation from accelerometer to the "IMU" gyroscope frame frame.
Definition: VioManagerOptions.h:205
ov_type
RESET
#define RESET
ov_msckf::VioManager::distance
double distance
Definition: VioManager.h:220
ov_msckf::VioManagerOptions::print_and_load_estimator
void print_and_load_estimator(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all estimator settings loaded. This allows for visual checking that...
Definition: VioManagerOptions.h:109
ov_core::TrackKLT
ov_msckf::VioManager::rT7
boost::posix_time::ptime rT7
Definition: VioManager.h:216
ov_msckf::VioManagerOptions::state_options
StateOptions state_options
Core state options (e.g. number of cameras, use fej, stereo, what calibration to enable etc)
Definition: VioManagerOptions.h:74
Feature.h
FeatureDatabase.h
ov_msckf::VioManagerOptions
Struct which stores all options needed for state estimation.
Definition: VioManagerOptions.h:56
ov_msckf::VioManager::updaterSLAM
std::shared_ptr< UpdaterSLAM > updaterSLAM
Our SLAM/ARUCO feature updater.
Definition: VioManager.h:204
ov_msckf::StateOptions::num_cameras
int num_cameras
Number of distinct cameras that we will observe features in.
Definition: StateOptions.h:83
ov_msckf::VioManager::timelastupdate
double timelastupdate
Definition: VioManager.h:219
State.h
ov_msckf::VioManager::updaterMSCKF
std::shared_ptr< UpdaterMSCKF > updaterMSCKF
Our MSCKF feature updater.
Definition: VioManager.h:201
ov_msckf::VioManagerOptions::zupt_options
UpdaterOptions zupt_options
Update options for zero velocity (chi2 multiplier)
Definition: VioManagerOptions.h:148
ov_msckf::VioManagerOptions::vec_da
Eigen::Matrix< double, 6, 1 > vec_da
Accelerometer IMU intrinsics (scale imperfection and axis misalignment, column-wise,...
Definition: VioManagerOptions.h:196
ov_core::TrackDescriptor
ov_core::ImuData::timestamp
double timestamp
ov_msckf::VioManagerOptions::knn_ratio
double knn_ratio
KNN ration between top two descriptor matcher which is required to be a good match.
Definition: VioManagerOptions.h:439
UpdaterMSCKF.h
ov_msckf::VioManagerOptions::print_and_load_noise
void print_and_load_noise(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all noise parameters loaded. This allows for visual checking that e...
Definition: VioManagerOptions.h:156
ov_msckf::VioManagerOptions::record_timing_filepath
std::string record_timing_filepath
The path to the file we will record the timing information into.
Definition: VioManagerOptions.h:101
ov_msckf::VioManagerOptions::print_and_load_state
void print_and_load_state(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load and print all state parameters (e.g. sensor extrinsics) This allows for visua...
Definition: VioManagerOptions.h:228
ov_core
RED
RED
ov_msckf::VioManager::retriangulate_active_tracks
void retriangulate_active_tracks(const ov_core::CameraData &message)
This function will will re-triangulate all features in the current frame.
Definition: VioManagerHelper.cpp:190
PRINT_WARNING
#define PRINT_WARNING(x...)
ov_msckf::VioManager::propagator
std::shared_ptr< Propagator > propagator
Propagator of our state.
Definition: VioManager.h:186


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