UpdaterZeroVelocity.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 "UpdaterZeroVelocity.h"
23 
24 #include "UpdaterHelper.h"
25 
26 #include "feat/FeatureDatabase.h"
27 #include "feat/FeatureHelper.h"
28 #include "state/Propagator.h"
29 #include "state/State.h"
30 #include "state/StateHelper.h"
31 #include "utils/colors.h"
32 #include "utils/print.h"
33 #include "utils/quat_ops.h"
34 
35 #include <boost/date_time/posix_time/posix_time.hpp>
36 #include <boost/math/distributions/chi_squared.hpp>
37 
38 using namespace ov_core;
39 using namespace ov_type;
40 using namespace ov_msckf;
41 
42 UpdaterZeroVelocity::UpdaterZeroVelocity(UpdaterOptions &options, NoiseManager &noises, std::shared_ptr<ov_core::FeatureDatabase> db,
43  std::shared_ptr<Propagator> prop, double gravity_mag, double zupt_max_velocity,
44  double zupt_noise_multiplier, double zupt_max_disparity)
45  : _options(options), _noises(noises), _db(db), _prop(prop), _zupt_max_velocity(zupt_max_velocity),
46  _zupt_noise_multiplier(zupt_noise_multiplier), _zupt_max_disparity(zupt_max_disparity) {
47 
48  // Gravity
49  _gravity << 0.0, 0.0, gravity_mag;
50 
51  // Save our raw pixel noise squared
52  _noises.sigma_w_2 = std::pow(_noises.sigma_w, 2);
53  _noises.sigma_a_2 = std::pow(_noises.sigma_a, 2);
54  _noises.sigma_wb_2 = std::pow(_noises.sigma_wb, 2);
55  _noises.sigma_ab_2 = std::pow(_noises.sigma_ab, 2);
56 
57  // Initialize the chi squared test table with confidence level 0.95
58  // https://github.com/KumarRobotics/msckf_vio/blob/050c50defa5a7fd9a04c1eed5687b405f02919b5/src/msckf_vio.cpp#L215-L221
59  for (int i = 1; i < 1000; i++) {
60  boost::math::chi_squared chi_squared_dist(i);
61  chi_squared_table[i] = boost::math::quantile(chi_squared_dist, 0.95);
62  }
63 }
64 
65 bool UpdaterZeroVelocity::try_update(std::shared_ptr<State> state, double timestamp) {
66 
67  // Return if we don't have any imu data yet
68  if (imu_data.empty()) {
70  return false;
71  }
72 
73  // Return if the state is already at the desired time
74  if (state->_timestamp == timestamp) {
76  return false;
77  }
78 
79  // Set the last time offset value if we have just started the system up
81  last_prop_time_offset = state->_calib_dt_CAMtoIMU->value()(0);
83  }
84 
85  // assert that the time we are requesting is in the future
86  // assert(timestamp > state->_timestamp);
87 
88  // Get what our IMU-camera offset should be (t_imu = t_cam + calib_dt)
89  double t_off_new = state->_calib_dt_CAMtoIMU->value()(0);
90 
91  // First lets construct an IMU vector of measurements we need
92  // double time0 = state->_timestamp+t_off_new;
93  double time0 = state->_timestamp + last_prop_time_offset;
94  double time1 = timestamp + t_off_new;
95 
96  // Select bounding inertial measurements
97  std::vector<ov_core::ImuData> imu_recent = Propagator::select_imu_readings(imu_data, time0, time1);
98 
99  // Move forward in time
100  last_prop_time_offset = t_off_new;
101 
102  // Check that we have at least one measurement to propagate with
103  if (imu_recent.size() < 2) {
104  PRINT_WARNING(RED "[ZUPT]: There are no IMU data to check for zero velocity with!!\n" RESET);
106  return false;
107  }
108 
109  // If we should integrate the acceleration and say the velocity should be zero
110  // Also if we should still inflate the bias based on their random walk noises
111  bool integrated_accel_constraint = false; // untested
112  bool model_time_varying_bias = true;
113  bool override_with_disparity_check = true;
114  bool explicitly_enforce_zero_motion = false;
115 
116  // Order of our Jacobian
117  std::vector<std::shared_ptr<Type>> Hx_order;
118  Hx_order.push_back(state->_imu->q());
119  Hx_order.push_back(state->_imu->bg());
120  Hx_order.push_back(state->_imu->ba());
121  if (integrated_accel_constraint) {
122  Hx_order.push_back(state->_imu->v());
123  }
124 
125  // Large final matrices used for update (we will compress these)
126  int h_size = (integrated_accel_constraint) ? 12 : 9;
127  int m_size = 6 * ((int)imu_recent.size() - 1);
128  Eigen::MatrixXd H = Eigen::MatrixXd::Zero(m_size, h_size);
129  Eigen::VectorXd res = Eigen::VectorXd::Zero(m_size);
130 
131  // IMU intrinsic calibration estimates (static)
132  Eigen::Matrix3d Dw = State::Dm(state->_options.imu_model, state->_calib_imu_dw->value());
133  Eigen::Matrix3d Da = State::Dm(state->_options.imu_model, state->_calib_imu_da->value());
134  Eigen::Matrix3d Tg = State::Tg(state->_calib_imu_tg->value());
135 
136  // Loop through all our IMU and construct the residual and Jacobian
137  // TODO: should add jacobians here in respect to IMU intrinsics!!
138  // State order is: [q_GtoI, bg, ba, v_IinG]
139  // Measurement order is: [w_true = 0, a_true = 0 or v_k+1 = 0]
140  // w_true = w_m - bw - nw
141  // a_true = a_m - ba - R*g - na
142  // v_true = v_k - g*dt + R^T*(a_m - ba - na)*dt
143  double dt_summed = 0;
144  for (size_t i = 0; i < imu_recent.size() - 1; i++) {
145 
146  // Precomputed values
147  double dt = imu_recent.at(i + 1).timestamp - imu_recent.at(i).timestamp;
148  Eigen::Vector3d a_hat = state->_calib_imu_ACCtoIMU->Rot() * Da * (imu_recent.at(i).am - state->_imu->bias_a());
149  Eigen::Vector3d w_hat = state->_calib_imu_GYROtoIMU->Rot() * Dw * (imu_recent.at(i).wm - state->_imu->bias_g() - Tg * a_hat);
150 
151  // Measurement noise (convert from continuous to discrete)
152  // NOTE: The dt time might be different if we have "cut" any imu measurements
153  // NOTE: We are performing "whittening" thus, we will decompose R_meas^-1 = L*L^t
154  // NOTE: This is then multiplied to the residual and Jacobian (equivalent to just updating with R_meas)
155  // NOTE: See Maybeck Stochastic Models, Estimation, and Control Vol. 1 Equations (7-21a)-(7-21c)
156  double w_omega = std::sqrt(dt) / _noises.sigma_w;
157  double w_accel = std::sqrt(dt) / _noises.sigma_a;
158  double w_accel_v = 1.0 / (std::sqrt(dt) * _noises.sigma_a);
159 
160  // Measurement residual (true value is zero)
161  res.block(6 * i + 0, 0, 3, 1) = -w_omega * w_hat;
162  if (!integrated_accel_constraint) {
163  res.block(6 * i + 3, 0, 3, 1) = -w_accel * (a_hat - state->_imu->Rot() * _gravity);
164  } else {
165  res.block(6 * i + 3, 0, 3, 1) = -w_accel_v * (state->_imu->vel() - _gravity * dt + state->_imu->Rot().transpose() * a_hat * dt);
166  }
167 
168  // Measurement Jacobian
169  Eigen::Matrix3d R_GtoI_jacob = (state->_options.do_fej) ? state->_imu->Rot_fej() : state->_imu->Rot();
170  H.block(6 * i + 0, 3, 3, 3) = -w_omega * Eigen::Matrix3d::Identity();
171  if (!integrated_accel_constraint) {
172  H.block(6 * i + 3, 0, 3, 3) = -w_accel * skew_x(R_GtoI_jacob * _gravity);
173  H.block(6 * i + 3, 6, 3, 3) = -w_accel * Eigen::Matrix3d::Identity();
174  } else {
175  H.block(6 * i + 3, 0, 3, 3) = -w_accel_v * R_GtoI_jacob.transpose() * skew_x(a_hat) * dt;
176  H.block(6 * i + 3, 6, 3, 3) = -w_accel_v * R_GtoI_jacob.transpose() * dt;
177  H.block(6 * i + 3, 9, 3, 3) = w_accel_v * Eigen::Matrix3d::Identity();
178  }
179  dt_summed += dt;
180  }
181 
182  // Compress the system (we should be over determined)
184  if (H.rows() < 1) {
185  return false;
186  }
187 
188  // Multiply our noise matrix by a fixed amount
189  // We typically need to treat the IMU as being "worst" to detect / not become overconfident
190  Eigen::MatrixXd R = _zupt_noise_multiplier * Eigen::MatrixXd::Identity(res.rows(), res.rows());
191 
192  // Next propagate the biases forward in time
193  // NOTE: G*Qd*G^t = dt*Qd*dt = dt*(1/dt*Qc)*dt = dt*Qc
194  Eigen::MatrixXd Q_bias = Eigen::MatrixXd::Identity(6, 6);
195  Q_bias.block(0, 0, 3, 3) *= dt_summed * _noises.sigma_wb_2;
196  Q_bias.block(3, 3, 3, 3) *= dt_summed * _noises.sigma_ab_2;
197 
198  // Chi2 distance check
199  // NOTE: we also append the propagation we "would do before the update" if this was to be accepted (just the bias evolution)
200  // NOTE: we don't propagate first since if we fail the chi2 then we just want to return and do normal logic
201  Eigen::MatrixXd P_marg = StateHelper::get_marginal_covariance(state, Hx_order);
202  if (model_time_varying_bias) {
203  P_marg.block(3, 3, 6, 6) += Q_bias;
204  }
205  Eigen::MatrixXd S = H * P_marg * H.transpose() + R;
206  double chi2 = res.dot(S.llt().solve(res));
207 
208  // Get our threshold (we precompute up to 1000 but handle the case that it is more)
209  double chi2_check;
210  if (res.rows() < 1000) {
211  chi2_check = chi_squared_table[res.rows()];
212  } else {
213  boost::math::chi_squared chi_squared_dist(res.rows());
214  chi2_check = boost::math::quantile(chi_squared_dist, 0.95);
215  PRINT_WARNING(YELLOW "[ZUPT]: chi2_check over the residual limit - %d\n" RESET, (int)res.rows());
216  }
217 
218  // Check if the image disparity
219  bool disparity_passed = false;
220  if (override_with_disparity_check) {
221 
222  // Get the disparity statistics from this image to the previous
223  double time0_cam = state->_timestamp;
224  double time1_cam = timestamp;
225  int num_features = 0;
226  double disp_avg = 0.0;
227  double disp_var = 0.0;
228  FeatureHelper::compute_disparity(_db, time0_cam, time1_cam, disp_avg, disp_var, num_features);
229 
230  // Check if this disparity is enough to be classified as moving
231  disparity_passed = (disp_avg < _zupt_max_disparity && num_features > 20);
232  if (disparity_passed) {
233  PRINT_INFO(CYAN "[ZUPT]: passed disparity (%.3f < %.3f, %d features)\n" RESET, disp_avg, _zupt_max_disparity, (int)num_features);
234  } else {
235  PRINT_DEBUG(YELLOW "[ZUPT]: failed disparity (%.3f > %.3f, %d features)\n" RESET, disp_avg, _zupt_max_disparity, (int)num_features);
236  }
237  }
238 
239  // Check if we are currently zero velocity
240  // We need to pass the chi2 and not be above our velocity threshold
241  if (!disparity_passed && (chi2 > _options.chi2_multipler * chi2_check || state->_imu->vel().norm() > _zupt_max_velocity)) {
243  last_zupt_count = 0;
244  PRINT_DEBUG(YELLOW "[ZUPT]: rejected |v_IinG| = %.3f (chi2 %.3f > %.3f)\n" RESET, state->_imu->vel().norm(), chi2,
245  _options.chi2_multipler * chi2_check);
246  return false;
247  }
248  PRINT_INFO(CYAN "[ZUPT]: accepted |v_IinG| = %.3f (chi2 %.3f < %.3f)\n" RESET, state->_imu->vel().norm(), chi2,
249  _options.chi2_multipler * chi2_check);
250 
251  // Do our update, only do this update if we have previously detected
252  // If we have succeeded, then we should remove the current timestamp feature tracks
253  // This is because we will not clone at this timestep and instead do our zero velocity update
254  // NOTE: We want to keep the tracks from the second time we have called the zv-upt since this won't have a clone
255  // NOTE: All future times after the second call to this function will also *not* have a clone, so we can remove those
256  if (last_zupt_count >= 2) {
257  _db->cleanup_measurements_exact(last_zupt_state_timestamp);
258  }
259 
260  // Else we are good, update the system
261  // 1) update with our IMU measurements directly
262  // 2) propagate and then explicitly say that our ori, pos, and vel should be zero
263  if (!explicitly_enforce_zero_motion) {
264 
265  // Next propagate the biases forward in time
266  // NOTE: G*Qd*G^t = dt*Qd*dt = dt*Qc
267  if (model_time_varying_bias) {
268  Eigen::MatrixXd Phi_bias = Eigen::MatrixXd::Identity(6, 6);
269  std::vector<std::shared_ptr<Type>> Phi_order;
270  Phi_order.push_back(state->_imu->bg());
271  Phi_order.push_back(state->_imu->ba());
272  StateHelper::EKFPropagation(state, Phi_order, Phi_order, Phi_bias, Q_bias);
273  }
274 
275  // Finally move the state time forward
276  StateHelper::EKFUpdate(state, Hx_order, H, res, R);
277  state->_timestamp = timestamp;
278 
279  } else {
280 
281  // Propagate the state forward in time
282  double time0_cam = last_zupt_state_timestamp;
283  double time1_cam = timestamp;
284  _prop->propagate_and_clone(state, time1_cam);
285 
286  // Create the update system!
287  H = Eigen::MatrixXd::Zero(9, 15);
288  res = Eigen::VectorXd::Zero(9);
289  R = Eigen::MatrixXd::Identity(9, 9);
290 
291  // residual (order is ori, pos, vel)
292  Eigen::Matrix3d R_GtoI0 = state->_clones_IMU.at(time0_cam)->Rot();
293  Eigen::Vector3d p_I0inG = state->_clones_IMU.at(time0_cam)->pos();
294  Eigen::Matrix3d R_GtoI1 = state->_clones_IMU.at(time1_cam)->Rot();
295  Eigen::Vector3d p_I1inG = state->_clones_IMU.at(time1_cam)->pos();
296  res.block(0, 0, 3, 1) = -log_so3(R_GtoI0 * R_GtoI1.transpose());
297  res.block(3, 0, 3, 1) = p_I1inG - p_I0inG;
298  res.block(6, 0, 3, 1) = state->_imu->vel();
299  res *= -1;
300 
301  // jacobian (order is q0, p0, q1, p1, v0)
302  Hx_order.clear();
303  Hx_order.push_back(state->_clones_IMU.at(time0_cam));
304  Hx_order.push_back(state->_clones_IMU.at(time1_cam));
305  Hx_order.push_back(state->_imu->v());
306  if (state->_options.do_fej) {
307  R_GtoI0 = state->_clones_IMU.at(time0_cam)->Rot_fej();
308  }
309  H.block(0, 0, 3, 3) = Eigen::Matrix3d::Identity();
310  H.block(0, 6, 3, 3) = -R_GtoI0;
311  H.block(3, 3, 3, 3) = -Eigen::Matrix3d::Identity();
312  H.block(3, 9, 3, 3) = Eigen::Matrix3d::Identity();
313  H.block(6, 12, 3, 3) = Eigen::Matrix3d::Identity();
314 
315  // noise (order is ori, pos, vel)
316  R.block(0, 0, 3, 3) *= std::pow(1e-2, 2);
317  R.block(3, 3, 3, 3) *= std::pow(1e-1, 2);
318  R.block(6, 6, 3, 3) *= std::pow(1e-1, 2);
319 
320  // finally update and remove the old clone
321  StateHelper::EKFUpdate(state, Hx_order, H, res, R);
322  StateHelper::marginalize(state, state->_clones_IMU.at(time1_cam));
323  state->_clones_IMU.erase(time1_cam);
324  }
325 
326  // Finally return
327  last_zupt_state_timestamp = timestamp;
328  last_zupt_count++;
329  return true;
330 }
Propagator.h
ov_msckf::NoiseManager::sigma_a_2
double sigma_a_2
Accelerometer white noise covariance.
Definition: NoiseManager.h:52
ov_msckf::UpdaterZeroVelocity::_db
std::shared_ptr< ov_core::FeatureDatabase > _db
Feature tracker database with all features in it.
Definition: UpdaterZeroVelocity.h:125
skew_x
Eigen::Matrix< double, 3, 3 > skew_x(const Eigen::Matrix< double, 3, 1 > &w)
ov_msckf::NoiseManager::sigma_a
double sigma_a
Accelerometer white noise (m/s^2/sqrt(hz))
Definition: NoiseManager.h:49
ov_msckf::UpdaterZeroVelocity::have_last_prop_time_offset
bool have_last_prop_time_offset
Definition: UpdaterZeroVelocity.h:150
quat_ops.h
ov_msckf::UpdaterZeroVelocity::try_update
bool try_update(std::shared_ptr< State > state, double timestamp)
Will first detect if the system is zero velocity, then will update.
Definition: UpdaterZeroVelocity.cpp:65
ov_msckf::State::Dm
static Eigen::Matrix3d Dm(StateOptions::ImuModel imu_model, const Eigen::MatrixXd &vec)
Gyroscope and accelerometer intrinsic matrix (scale imperfection and axis misalignment)
Definition: State.h:91
ov_msckf::UpdaterZeroVelocity::last_zupt_state_timestamp
double last_zupt_state_timestamp
Last timestamp we did zero velocity update with.
Definition: UpdaterZeroVelocity.h:153
UpdaterHelper.h
ov_msckf::UpdaterOptions
Struct which stores general updater options.
Definition: UpdaterOptions.h:32
YELLOW
YELLOW
ov_msckf::NoiseManager::sigma_wb
double sigma_wb
Gyroscope random walk (rad/s^2/sqrt(hz))
Definition: NoiseManager.h:43
PRINT_DEBUG
#define PRINT_DEBUG(x...)
ov_msckf::UpdaterZeroVelocity::imu_data
std::vector< ov_core::ImuData > imu_data
Our history of IMU messages (time, angular, linear)
Definition: UpdaterZeroVelocity.h:146
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::NoiseManager::sigma_wb_2
double sigma_wb_2
Gyroscope random walk covariance.
Definition: NoiseManager.h:46
ov_msckf::NoiseManager::sigma_ab
double sigma_ab
Accelerometer random walk (m/s^3/sqrt(hz))
Definition: NoiseManager.h:55
ov_msckf::UpdaterZeroVelocity::_prop
std::shared_ptr< Propagator > _prop
Our propagator!
Definition: UpdaterZeroVelocity.h:128
ov_msckf::UpdaterZeroVelocity::_zupt_noise_multiplier
double _zupt_noise_multiplier
Multiplier of our IMU noise matrix (default should be 1.0)
Definition: UpdaterZeroVelocity.h:137
ov_msckf::UpdaterZeroVelocity::_zupt_max_velocity
double _zupt_max_velocity
Max velocity (m/s) that we should consider a zupt with.
Definition: UpdaterZeroVelocity.h:134
StateHelper.h
UpdaterZeroVelocity.h
ov_msckf::NoiseManager::sigma_w
double sigma_w
Gyroscope white noise (rad/s/sqrt(hz))
Definition: NoiseManager.h:37
FeatureHelper.h
ov_msckf::UpdaterZeroVelocity::last_prop_time_offset
double last_prop_time_offset
Estimate for time offset at last propagation time.
Definition: UpdaterZeroVelocity.h:149
ov_msckf::StateHelper::EKFUpdate
static void EKFUpdate(std::shared_ptr< State > state, const std::vector< std::shared_ptr< ov_type::Type >> &H_order, const Eigen::MatrixXd &H, const Eigen::VectorXd &res, const Eigen::MatrixXd &R)
Performs EKF update of the state (see Linear Measurement Update page)
Definition: StateHelper.cpp:116
ov_msckf::StateHelper::get_marginal_covariance
static Eigen::MatrixXd get_marginal_covariance(std::shared_ptr< State > state, const std::vector< std::shared_ptr< ov_type::Type >> &small_variables)
For a given set of variables, this will this will calculate a smaller covariance.
Definition: StateHelper.cpp:226
ov_msckf::UpdaterHelper::measurement_compress_inplace
static void measurement_compress_inplace(Eigen::MatrixXd &H_x, Eigen::VectorXd &res)
This will perform measurement compression.
Definition: UpdaterHelper.cpp:456
ov_msckf::NoiseManager::sigma_ab_2
double sigma_ab_2
Accelerometer random walk covariance.
Definition: NoiseManager.h:58
ov_msckf::StateHelper::EKFPropagation
static void EKFPropagation(std::shared_ptr< State > state, const std::vector< std::shared_ptr< ov_type::Type >> &order_NEW, const std::vector< std::shared_ptr< ov_type::Type >> &order_OLD, const Eigen::MatrixXd &Phi, const Eigen::MatrixXd &Q)
Performs EKF propagation of the state covariance.
Definition: StateHelper.cpp:36
ov_msckf::Propagator::select_imu_readings
static std::vector< ov_core::ImuData > select_imu_readings(const std::vector< ov_core::ImuData > &imu_data, double time0, double time1, bool warn=true)
Helper function that given current imu data, will select imu readings between the two times.
Definition: Propagator.cpp:269
print.h
colors.h
ov_msckf::State::Tg
static Eigen::Matrix3d Tg(const Eigen::MatrixXd &vec)
Gyroscope gravity sensitivity.
Definition: State.h:110
PRINT_INFO
#define PRINT_INFO(x...)
ov_type
RESET
#define RESET
FeatureDatabase.h
ov_msckf::UpdaterZeroVelocity::_options
UpdaterOptions _options
Options used during update (chi2 multiplier)
Definition: UpdaterZeroVelocity.h:119
ov_msckf::NoiseManager::sigma_w_2
double sigma_w_2
Gyroscope white noise covariance.
Definition: NoiseManager.h:40
State.h
ov_msckf::UpdaterZeroVelocity::_noises
NoiseManager _noises
Container for the imu noise values.
Definition: UpdaterZeroVelocity.h:122
ov_msckf::UpdaterZeroVelocity::_zupt_max_disparity
double _zupt_max_disparity
Max disparity (pixels) that we should consider a zupt with.
Definition: UpdaterZeroVelocity.h:140
ov_msckf::UpdaterZeroVelocity::_gravity
Eigen::Vector3d _gravity
Gravity vector.
Definition: UpdaterZeroVelocity.h:131
log_so3
Eigen::Matrix< double, 3, 1 > log_so3(const Eigen::Matrix< double, 3, 3 > &R)
ov_msckf::UpdaterZeroVelocity::chi_squared_table
std::map< int, double > chi_squared_table
Chi squared 95th percentile table (lookup would be size of residual)
Definition: UpdaterZeroVelocity.h:143
ov_msckf::StateHelper::marginalize
static void marginalize(std::shared_ptr< State > state, std::shared_ptr< ov_type::Type > marg)
Marginalizes a variable, properly modifying the ordering/covariances in the state.
Definition: StateHelper.cpp:271
ov_msckf::NoiseManager
Struct of our imu noise parameters.
Definition: NoiseManager.h:34
ov_msckf::UpdaterZeroVelocity::last_zupt_count
int last_zupt_count
Number of times we have called update.
Definition: UpdaterZeroVelocity.h:156
ov_core
RED
RED
PRINT_WARNING
#define PRINT_WARNING(x...)
CYAN
CYAN
ov_msckf::UpdaterOptions::chi2_multipler
double chi2_multipler
What chi-squared multipler we should apply.
Definition: UpdaterOptions.h:35


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