UpdaterMSCKF.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 "UpdaterMSCKF.h"
23 
24 #include "UpdaterHelper.h"
25 
26 #include "feat/Feature.h"
28 #include "state/State.h"
29 #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 UpdaterMSCKF::UpdaterMSCKF(UpdaterOptions &options, ov_core::FeatureInitializerOptions &feat_init_options) : _options(options) {
43 
44  // Save our raw pixel noise squared
45  _options.sigma_pix_sq = std::pow(_options.sigma_pix, 2);
46 
47  // Save our feature initializer
48  initializer_feat = std::shared_ptr<ov_core::FeatureInitializer>(new ov_core::FeatureInitializer(feat_init_options));
49 
50  // Initialize the chi squared test table with confidence level 0.95
51  // https://github.com/KumarRobotics/msckf_vio/blob/050c50defa5a7fd9a04c1eed5687b405f02919b5/src/msckf_vio.cpp#L215-L221
52  for (int i = 1; i < 500; i++) {
53  boost::math::chi_squared chi_squared_dist(i);
54  chi_squared_table[i] = boost::math::quantile(chi_squared_dist, 0.95);
55  }
56 }
57 
58 void UpdaterMSCKF::update(std::shared_ptr<State> state, std::vector<std::shared_ptr<Feature>> &feature_vec) {
59 
60  // Return if no features
61  if (feature_vec.empty())
62  return;
63 
64  // Start timing
65  boost::posix_time::ptime rT0, rT1, rT2, rT3, rT4, rT5;
66  rT0 = boost::posix_time::microsec_clock::local_time();
67 
68  // 0. Get all timestamps our clones are at (and thus valid measurement times)
69  std::vector<double> clonetimes;
70  for (const auto &clone_imu : state->_clones_IMU) {
71  clonetimes.emplace_back(clone_imu.first);
72  }
73 
74  // 1. Clean all feature measurements and make sure they all have valid clone times
75  auto it0 = feature_vec.begin();
76  while (it0 != feature_vec.end()) {
77 
78  // Clean the feature
79  (*it0)->clean_old_measurements(clonetimes);
80 
81  // Count how many measurements
82  int ct_meas = 0;
83  for (const auto &pair : (*it0)->timestamps) {
84  ct_meas += (*it0)->timestamps[pair.first].size();
85  }
86 
87  // Remove if we don't have enough
88  if (ct_meas < 2) {
89  (*it0)->to_delete = true;
90  it0 = feature_vec.erase(it0);
91  } else {
92  it0++;
93  }
94  }
95  rT1 = boost::posix_time::microsec_clock::local_time();
96 
97  // 2. Create vector of cloned *CAMERA* poses at each of our clone timesteps
98  std::unordered_map<size_t, std::unordered_map<double, FeatureInitializer::ClonePose>> clones_cam;
99  for (const auto &clone_calib : state->_calib_IMUtoCAM) {
100 
101  // For this camera, create the vector of camera poses
102  std::unordered_map<double, FeatureInitializer::ClonePose> clones_cami;
103  for (const auto &clone_imu : state->_clones_IMU) {
104 
105  // Get current camera pose
106  Eigen::Matrix<double, 3, 3> R_GtoCi = clone_calib.second->Rot() * clone_imu.second->Rot();
107  Eigen::Matrix<double, 3, 1> p_CioinG = clone_imu.second->pos() - R_GtoCi.transpose() * clone_calib.second->pos();
108 
109  // Append to our map
110  clones_cami.insert({clone_imu.first, FeatureInitializer::ClonePose(R_GtoCi, p_CioinG)});
111  }
112 
113  // Append to our map
114  clones_cam.insert({clone_calib.first, clones_cami});
115  }
116 
117  // 3. Try to triangulate all MSCKF or new SLAM features that have measurements
118  auto it1 = feature_vec.begin();
119  while (it1 != feature_vec.end()) {
120 
121  // Triangulate the feature and remove if it fails
122  bool success_tri = true;
123  if (initializer_feat->config().triangulate_1d) {
124  success_tri = initializer_feat->single_triangulation_1d(*it1, clones_cam);
125  } else {
126  success_tri = initializer_feat->single_triangulation(*it1, clones_cam);
127  }
128 
129  // Gauss-newton refine the feature
130  bool success_refine = true;
131  if (initializer_feat->config().refine_features) {
132  success_refine = initializer_feat->single_gaussnewton(*it1, clones_cam);
133  }
134 
135  // Remove the feature if not a success
136  if (!success_tri || !success_refine) {
137  (*it1)->to_delete = true;
138  it1 = feature_vec.erase(it1);
139  continue;
140  }
141  it1++;
142  }
143  rT2 = boost::posix_time::microsec_clock::local_time();
144 
145  // Calculate the max possible measurement size
146  size_t max_meas_size = 0;
147  for (size_t i = 0; i < feature_vec.size(); i++) {
148  for (const auto &pair : feature_vec.at(i)->timestamps) {
149  max_meas_size += 2 * feature_vec.at(i)->timestamps[pair.first].size();
150  }
151  }
152 
153  // Calculate max possible state size (i.e. the size of our covariance)
154  // NOTE: that when we have the single inverse depth representations, those are only 1dof in size
155  size_t max_hx_size = state->max_covariance_size();
156  for (auto &landmark : state->_features_SLAM) {
157  max_hx_size -= landmark.second->size();
158  }
159 
160  // Large Jacobian and residual of *all* features for this update
161  Eigen::VectorXd res_big = Eigen::VectorXd::Zero(max_meas_size);
162  Eigen::MatrixXd Hx_big = Eigen::MatrixXd::Zero(max_meas_size, max_hx_size);
163  std::unordered_map<std::shared_ptr<Type>, size_t> Hx_mapping;
164  std::vector<std::shared_ptr<Type>> Hx_order_big;
165  size_t ct_jacob = 0;
166  size_t ct_meas = 0;
167 
168  // 4. Compute linear system for each feature, nullspace project, and reject
169  auto it2 = feature_vec.begin();
170  while (it2 != feature_vec.end()) {
171 
172  // Convert our feature into our current format
174  feat.featid = (*it2)->featid;
175  feat.uvs = (*it2)->uvs;
176  feat.uvs_norm = (*it2)->uvs_norm;
177  feat.timestamps = (*it2)->timestamps;
178 
179  // If we are using single inverse depth, then it is equivalent to using the msckf inverse depth
180  feat.feat_representation = state->_options.feat_rep_msckf;
181  if (state->_options.feat_rep_msckf == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
182  feat.feat_representation = LandmarkRepresentation::Representation::ANCHORED_MSCKF_INVERSE_DEPTH;
183  }
184 
185  // Save the position and its fej value
186  if (LandmarkRepresentation::is_relative_representation(feat.feat_representation)) {
187  feat.anchor_cam_id = (*it2)->anchor_cam_id;
188  feat.anchor_clone_timestamp = (*it2)->anchor_clone_timestamp;
189  feat.p_FinA = (*it2)->p_FinA;
190  feat.p_FinA_fej = (*it2)->p_FinA;
191  } else {
192  feat.p_FinG = (*it2)->p_FinG;
193  feat.p_FinG_fej = (*it2)->p_FinG;
194  }
195 
196  // Our return values (feature jacobian, state jacobian, residual, and order of state jacobian)
197  Eigen::MatrixXd H_f;
198  Eigen::MatrixXd H_x;
199  Eigen::VectorXd res;
200  std::vector<std::shared_ptr<Type>> Hx_order;
201 
202  // Get the Jacobian for this feature
203  UpdaterHelper::get_feature_jacobian_full(state, feat, H_f, H_x, res, Hx_order);
204 
205  // Nullspace project
207 
209  Eigen::MatrixXd P_marg = StateHelper::get_marginal_covariance(state, Hx_order);
210  Eigen::MatrixXd S = H_x * P_marg * H_x.transpose();
211  S.diagonal() += _options.sigma_pix_sq * Eigen::VectorXd::Ones(S.rows());
212  double chi2 = res.dot(S.llt().solve(res));
213 
214  // Get our threshold (we precompute up to 500 but handle the case that it is more)
215  double chi2_check;
216  if (res.rows() < 500) {
217  chi2_check = chi_squared_table[res.rows()];
218  } else {
219  boost::math::chi_squared chi_squared_dist(res.rows());
220  chi2_check = boost::math::quantile(chi_squared_dist, 0.95);
221  PRINT_WARNING(YELLOW "chi2_check over the residual limit - %d\n" RESET, (int)res.rows());
222  }
223 
224  // Check if we should delete or not
225  if (chi2 > _options.chi2_multipler * chi2_check) {
226  (*it2)->to_delete = true;
227  it2 = feature_vec.erase(it2);
228  // PRINT_DEBUG("featid = %d\n", feat.featid);
229  // PRINT_DEBUG("chi2 = %f > %f\n", chi2, _options.chi2_multipler*chi2_check);
230  // std::stringstream ss;
231  // ss << "res = " << std::endl << res.transpose() << std::endl;
232  // PRINT_DEBUG(ss.str().c_str());
233  continue;
234  }
235 
236  // We are good!!! Append to our large H vector
237  size_t ct_hx = 0;
238  for (const auto &var : Hx_order) {
239 
240  // Ensure that this variable is in our Jacobian
241  if (Hx_mapping.find(var) == Hx_mapping.end()) {
242  Hx_mapping.insert({var, ct_jacob});
243  Hx_order_big.push_back(var);
244  ct_jacob += var->size();
245  }
246 
247  // Append to our large Jacobian
248  Hx_big.block(ct_meas, Hx_mapping[var], H_x.rows(), var->size()) = H_x.block(0, ct_hx, H_x.rows(), var->size());
249  ct_hx += var->size();
250  }
251 
252  // Append our residual and move forward
253  res_big.block(ct_meas, 0, res.rows(), 1) = res;
254  ct_meas += res.rows();
255  it2++;
256  }
257  rT3 = boost::posix_time::microsec_clock::local_time();
258 
259  // We have appended all features to our Hx_big, res_big
260  // Delete it so we do not reuse information
261  for (size_t f = 0; f < feature_vec.size(); f++) {
262  feature_vec[f]->to_delete = true;
263  }
264 
265  // Return if we don't have anything and resize our matrices
266  if (ct_meas < 1) {
267  return;
268  }
269  assert(ct_meas <= max_meas_size);
270  assert(ct_jacob <= max_hx_size);
271  res_big.conservativeResize(ct_meas, 1);
272  Hx_big.conservativeResize(ct_meas, ct_jacob);
273 
274  // 5. Perform measurement compression
276  if (Hx_big.rows() < 1) {
277  return;
278  }
279  rT4 = boost::posix_time::microsec_clock::local_time();
280 
281  // Our noise is isotropic, so make it here after our compression
282  Eigen::MatrixXd R_big = _options.sigma_pix_sq * Eigen::MatrixXd::Identity(res_big.rows(), res_big.rows());
283 
284  // 6. With all good features update the state
285  StateHelper::EKFUpdate(state, Hx_order_big, Hx_big, res_big, R_big);
286  rT5 = boost::posix_time::microsec_clock::local_time();
287 
288  // Debug print timing information
289  PRINT_ALL("[MSCKF-UP]: %.4f seconds to clean\n", (rT1 - rT0).total_microseconds() * 1e-6);
290  PRINT_ALL("[MSCKF-UP]: %.4f seconds to triangulate\n", (rT2 - rT1).total_microseconds() * 1e-6);
291  PRINT_ALL("[MSCKF-UP]: %.4f seconds create system (%d features)\n", (rT3 - rT2).total_microseconds() * 1e-6, (int)feature_vec.size());
292  PRINT_ALL("[MSCKF-UP]: %.4f seconds compress system\n", (rT4 - rT3).total_microseconds() * 1e-6);
293  PRINT_ALL("[MSCKF-UP]: %.4f seconds update state (%d size)\n", (rT5 - rT4).total_microseconds() * 1e-6, (int)res_big.rows());
294  PRINT_ALL("[MSCKF-UP]: %.4f seconds total\n", (rT5 - rT1).total_microseconds() * 1e-6);
295 }
ov_msckf::UpdaterHelper::UpdaterHelperFeature::anchor_cam_id
int anchor_cam_id
What camera ID our pose is anchored in!! By default the first measurement is the anchor.
Definition: UpdaterHelper.h:72
ov_msckf::UpdaterHelper::get_feature_jacobian_full
static void get_feature_jacobian_full(std::shared_ptr< State > state, UpdaterHelperFeature &feature, Eigen::MatrixXd &H_f, Eigen::MatrixXd &H_x, Eigen::VectorXd &res, std::vector< std::shared_ptr< ov_type::Type >> &x_order)
Will construct the "stacked" Jacobians for a single feature from all its measurements.
Definition: UpdaterHelper.cpp:192
ov_msckf::UpdaterHelper::UpdaterHelperFeature::p_FinA
Eigen::Vector3d p_FinA
Triangulated position of this feature, in the anchor frame.
Definition: UpdaterHelper.h:78
ov_msckf::UpdaterMSCKF::_options
UpdaterOptions _options
Options used during update.
Definition: UpdaterMSCKF.h:72
quat_ops.h
UpdaterHelper.h
ov_msckf::UpdaterOptions
Struct which stores general updater options.
Definition: UpdaterOptions.h:32
LandmarkRepresentation.h
ov_msckf::UpdaterHelper::UpdaterHelperFeature::uvs
std::unordered_map< size_t, std::vector< Eigen::VectorXf > > uvs
UV coordinates that this feature has been seen from (mapped by camera ID)
Definition: UpdaterHelper.h:60
YELLOW
YELLOW
ov_msckf::UpdaterHelper::UpdaterHelperFeature::featid
size_t featid
Unique ID of this feature.
Definition: UpdaterHelper.h:57
FeatureInitializer.h
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::UpdaterHelper::UpdaterHelperFeature
Feature object that our UpdaterHelper leverages, has all measurements and means.
Definition: UpdaterHelper.h:54
ov_msckf::UpdaterHelper::UpdaterHelperFeature::uvs_norm
std::unordered_map< size_t, std::vector< Eigen::VectorXf > > uvs_norm
Definition: UpdaterHelper.h:63
ov_core::FeatureInitializer
StateHelper.h
PRINT_ALL
#define PRINT_ALL(x...)
f
f
ov_core::FeatureInitializerOptions
ov_msckf::UpdaterMSCKF::initializer_feat
std::shared_ptr< ov_core::FeatureInitializer > initializer_feat
Feature initializer class object.
Definition: UpdaterMSCKF.h:75
ov_msckf::UpdaterHelper::UpdaterHelperFeature::feat_representation
ov_type::LandmarkRepresentation::Representation feat_representation
What representation our feature is in.
Definition: UpdaterHelper.h:69
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::UpdaterHelper::UpdaterHelperFeature::p_FinG
Eigen::Vector3d p_FinG
Triangulated position of this feature, in the global frame.
Definition: UpdaterHelper.h:84
ov_msckf::UpdaterHelper::UpdaterHelperFeature::p_FinA_fej
Eigen::Vector3d p_FinA_fej
Triangulated position of this feature, in the anchor frame first estimate.
Definition: UpdaterHelper.h:81
clonetimes
std::deque< double > clonetimes
print.h
ov_msckf::UpdaterMSCKF::chi_squared_table
std::map< int, double > chi_squared_table
Chi squared 95th percentile table (lookup would be size of residual)
Definition: UpdaterMSCKF.h:78
colors.h
ov_type
RESET
#define RESET
Feature.h
ov_msckf::UpdaterHelper::UpdaterHelperFeature::anchor_clone_timestamp
double anchor_clone_timestamp
Timestamp of anchor clone.
Definition: UpdaterHelper.h:75
ov_msckf::UpdaterMSCKF::update
void update(std::shared_ptr< State > state, std::vector< std::shared_ptr< ov_core::Feature >> &feature_vec)
Given tracked features, this will try to use them to update the state.
Definition: UpdaterMSCKF.cpp:58
ov_msckf::UpdaterOptions::sigma_pix
double sigma_pix
Noise sigma for our raw pixel measurements.
Definition: UpdaterOptions.h:38
State.h
ov_msckf::UpdaterHelper::UpdaterHelperFeature::p_FinG_fej
Eigen::Vector3d p_FinG_fej
Triangulated position of this feature, in the global frame first estimate.
Definition: UpdaterHelper.h:87
ov_msckf::UpdaterOptions::sigma_pix_sq
double sigma_pix_sq
Covariance for our raw pixel measurements.
Definition: UpdaterOptions.h:41
UpdaterMSCKF.h
ov_core
ov_msckf::UpdaterHelper::nullspace_project_inplace
static void nullspace_project_inplace(Eigen::MatrixXd &H_f, Eigen::MatrixXd &H_x, Eigen::VectorXd &res)
This will project the left nullspace of H_f onto the linear system.
Definition: UpdaterHelper.cpp:426
PRINT_WARNING
#define PRINT_WARNING(x...)
ov_msckf::UpdaterHelper::UpdaterHelperFeature::timestamps
std::unordered_map< size_t, std::vector< double > > timestamps
Timestamps of each UV measurement (mapped by camera ID)
Definition: UpdaterHelper.h:66
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