InertialInitializer.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 "InertialInitializer.h"
23 
26 
27 #include "feat/FeatureHelper.h"
28 #include "types/Type.h"
29 #include "utils/colors.h"
30 #include "utils/print.h"
31 #include "utils/quat_ops.h"
32 #include "utils/sensor_data.h"
33 
34 using namespace ov_core;
35 using namespace ov_type;
36 using namespace ov_init;
37 
38 InertialInitializer::InertialInitializer(InertialInitializerOptions &params_, std::shared_ptr<ov_core::FeatureDatabase> db)
39  : params(params_), _db(db) {
40 
41  // Vector of our IMU data
42  imu_data = std::make_shared<std::vector<ov_core::ImuData>>();
43 
44  // Create initializers
45  init_static = std::make_shared<StaticInitializer>(params, _db, imu_data);
46  init_dynamic = std::make_shared<DynamicInitializer>(params, _db, imu_data);
47 }
48 
49 void InertialInitializer::feed_imu(const ov_core::ImuData &message, double oldest_time) {
50 
51  // Append it to our vector
52  imu_data->emplace_back(message);
53 
54  // Sort our imu data (handles any out of order measurements)
55  // std::sort(imu_data->begin(), imu_data->end(), [](const IMUDATA i, const IMUDATA j) {
56  // return i.timestamp < j.timestamp;
57  //});
58 
59  // Loop through and delete imu messages that are older than our requested time
60  // std::cout << "INIT: imu_data.size() " << imu_data->size() << std::endl;
61  if (oldest_time != -1) {
62  auto it0 = imu_data->begin();
63  while (it0 != imu_data->end()) {
64  if (it0->timestamp < oldest_time) {
65  it0 = imu_data->erase(it0);
66  } else {
67  it0++;
68  }
69  }
70  }
71 }
72 
73 bool InertialInitializer::initialize(double &timestamp, Eigen::MatrixXd &covariance, std::vector<std::shared_ptr<ov_type::Type>> &order,
74  std::shared_ptr<ov_type::IMU> t_imu, bool wait_for_jerk) {
75 
76  // Get the newest and oldest timestamps we will try to initialize between!
77  double newest_cam_time = -1;
78  for (auto const &feat : _db->get_internal_data()) {
79  for (auto const &camtimepair : feat.second->timestamps) {
80  for (auto const &time : camtimepair.second) {
81  newest_cam_time = std::max(newest_cam_time, time);
82  }
83  }
84  }
85  double oldest_time = newest_cam_time - params.init_window_time - 0.10;
86  if (newest_cam_time < 0 || oldest_time < 0) {
87  return false;
88  }
89 
90  // Remove all measurements that are older then our initialization window
91  // Then we will try to use all features that are in the feature database!
92  _db->cleanup_measurements(oldest_time);
93  auto it_imu = imu_data->begin();
94  while (it_imu != imu_data->end() && it_imu->timestamp < oldest_time + params.calib_camimu_dt) {
95  it_imu = imu_data->erase(it_imu);
96  }
97 
98  // Compute the disparity of the system at the current timestep
99  // If disparity is zero or negative we will always use the static initializer
100  bool disparity_detected_moving_1to0 = false;
101  bool disparity_detected_moving_2to1 = false;
102  if (params.init_max_disparity > 0) {
103 
104  // Get the disparity statistics from this image to the previous
105  // Only compute the disparity for the oldest half of the initialization period
106  double newest_time_allowed = newest_cam_time - 0.5 * params.init_window_time;
107  int num_features0 = 0;
108  int num_features1 = 0;
109  double avg_disp0, avg_disp1;
110  double var_disp0, var_disp1;
111  FeatureHelper::compute_disparity(_db, avg_disp0, var_disp0, num_features0, newest_time_allowed);
112  FeatureHelper::compute_disparity(_db, avg_disp1, var_disp1, num_features1, newest_cam_time, newest_time_allowed);
113 
114  // Return if we can't compute the disparity
115  int feat_thresh = 15;
116  if (num_features0 < feat_thresh || num_features1 < feat_thresh) {
117  PRINT_WARNING(YELLOW "[init]: not enough feats to compute disp: %d,%d < %d\n" RESET, num_features0, num_features1, feat_thresh);
118  return false;
119  }
120 
121  // Check if it passed our check!
122  PRINT_INFO(YELLOW "[init]: disparity is %.3f,%.3f (%.2f thresh)\n" RESET, avg_disp0, avg_disp1, params.init_max_disparity);
123  disparity_detected_moving_1to0 = (avg_disp0 > params.init_max_disparity);
124  disparity_detected_moving_2to1 = (avg_disp1 > params.init_max_disparity);
125  }
126 
127  // Use our static initializer!
128  // CASE1: if our disparity says we were static in last window and have moved in the newest, we have a jerk
129  // CASE2: if both disparities are below the threshold, then the platform has been stationary during both periods
130  bool has_jerk = (!disparity_detected_moving_1to0 && disparity_detected_moving_2to1);
131  bool is_still = (!disparity_detected_moving_1to0 && !disparity_detected_moving_2to1);
132  if (((has_jerk && wait_for_jerk) || (is_still && !wait_for_jerk)) && params.init_imu_thresh > 0.0) {
133  PRINT_DEBUG(GREEN "[init]: USING STATIC INITIALIZER METHOD!\n" RESET);
134  return init_static->initialize(timestamp, covariance, order, t_imu, wait_for_jerk);
135  } else if (params.init_dyn_use && !is_still) {
136  PRINT_DEBUG(GREEN "[init]: USING DYNAMIC INITIALIZER METHOD!\n" RESET);
137  std::map<double, std::shared_ptr<ov_type::PoseJPL>> _clones_IMU;
138  std::unordered_map<size_t, std::shared_ptr<ov_type::Landmark>> _features_SLAM;
139  return init_dynamic->initialize(timestamp, covariance, order, t_imu, _clones_IMU, _features_SLAM);
140  } else {
141  std::string msg = (has_jerk) ? "" : "no accel jerk detected";
142  msg += (has_jerk || is_still) ? "" : ", ";
143  msg += (is_still) ? "" : "platform moving too much";
144  PRINT_INFO(YELLOW "[init]: failed static init: %s\n" RESET, msg.c_str());
145  }
146  return false;
147 }
ov_init::InertialInitializer::imu_data
std::shared_ptr< std::vector< ov_core::ImuData > > imu_data
Our history of IMU messages (time, angular, linear)
Definition: InertialInitializer.h:108
ov_init::InertialInitializer::initialize
bool initialize(double &timestamp, Eigen::MatrixXd &covariance, std::vector< std::shared_ptr< ov_type::Type >> &order, std::shared_ptr< ov_type::IMU > t_imu, bool wait_for_jerk=true)
Try to get the initialized system.
Definition: InertialInitializer.cpp:73
quat_ops.h
ov_init::InertialInitializerOptions
Struct which stores all options needed for state estimation.
Definition: InertialInitializerOptions.h:49
YELLOW
YELLOW
PRINT_DEBUG
#define PRINT_DEBUG(x...)
sensor_data.h
ov_init::InertialInitializerOptions::init_window_time
double init_window_time
Amount of time we will initialize over (seconds)
Definition: InertialInitializerOptions.h:64
ov_init::InertialInitializerOptions::init_dyn_use
bool init_dyn_use
If we should perform dynamic initialization.
Definition: InertialInitializerOptions.h:76
ov_init::InertialInitializer::init_static
std::shared_ptr< StaticInitializer > init_static
Static initialization helper class.
Definition: InertialInitializer.h:111
FeatureHelper.h
ov_init::InertialInitializerOptions::calib_camimu_dt
double calib_camimu_dt
Time offset between camera and IMU (t_imu = t_cam + t_off)
Definition: InertialInitializerOptions.h:246
InertialInitializer.h
ov_init::InertialInitializer::init_dynamic
std::shared_ptr< DynamicInitializer > init_dynamic
Dynamic initialization helper class.
Definition: InertialInitializer.h:114
ov_init::InertialInitializer::feed_imu
void feed_imu(const ov_core::ImuData &message, double oldest_time=-1)
Feed function for inertial data.
Definition: InertialInitializer.cpp:49
ov_init::InertialInitializer::_db
std::shared_ptr< ov_core::FeatureDatabase > _db
Feature tracker database with all features in it.
Definition: InertialInitializer.h:105
ov_init
State initialization code.
Definition: Factor_GenericPrior.h:27
ov_core::ImuData
GREEN
GREEN
ov_init::InertialInitializerOptions::init_imu_thresh
double init_imu_thresh
Variance threshold on our acceleration to be classified as moving.
Definition: InertialInitializerOptions.h:67
print.h
ov_init::InertialInitializerOptions::init_max_disparity
double init_max_disparity
Max disparity we will consider the unit to be stationary.
Definition: InertialInitializerOptions.h:70
colors.h
PRINT_INFO
#define PRINT_INFO(x...)
ov_type
RESET
#define RESET
ov_init::InertialInitializer::params
InertialInitializerOptions params
Initialization parameters.
Definition: InertialInitializer.h:102
Type.h
ov_core
PRINT_WARNING
#define PRINT_WARNING(x...)
StaticInitializer.h
DynamicInitializer.h


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