UpdaterSLAM.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 "UpdaterSLAM.h"
23 
24 #include "UpdaterHelper.h"
25 
26 #include "feat/Feature.h"
28 #include "state/State.h"
29 #include "state/StateHelper.h"
30 #include "types/Landmark.h"
32 #include "utils/colors.h"
33 #include "utils/print.h"
34 #include "utils/quat_ops.h"
35 
36 #include <boost/date_time/posix_time/posix_time.hpp>
37 #include <boost/math/distributions/chi_squared.hpp>
38 
39 using namespace ov_core;
40 using namespace ov_type;
41 using namespace ov_msckf;
42 
43 UpdaterSLAM::UpdaterSLAM(UpdaterOptions &options_slam, UpdaterOptions &options_aruco, ov_core::FeatureInitializerOptions &feat_init_options)
44  : _options_slam(options_slam), _options_aruco(options_aruco) {
45 
46  // Save our raw pixel noise squared
49 
50  // Save our feature initializer
51  initializer_feat = std::shared_ptr<ov_core::FeatureInitializer>(new ov_core::FeatureInitializer(feat_init_options));
52 
53  // Initialize the chi squared test table with confidence level 0.95
54  // https://github.com/KumarRobotics/msckf_vio/blob/050c50defa5a7fd9a04c1eed5687b405f02919b5/src/msckf_vio.cpp#L215-L221
55  for (int i = 1; i < 500; i++) {
56  boost::math::chi_squared chi_squared_dist(i);
57  chi_squared_table[i] = boost::math::quantile(chi_squared_dist, 0.95);
58  }
59 }
60 
61 void UpdaterSLAM::delayed_init(std::shared_ptr<State> state, std::vector<std::shared_ptr<Feature>> &feature_vec) {
62 
63  // Return if no features
64  if (feature_vec.empty())
65  return;
66 
67  // Start timing
68  boost::posix_time::ptime rT0, rT1, rT2, rT3;
69  rT0 = boost::posix_time::microsec_clock::local_time();
70 
71  // 0. Get all timestamps our clones are at (and thus valid measurement times)
72  std::vector<double> clonetimes;
73  for (const auto &clone_imu : state->_clones_IMU) {
74  clonetimes.emplace_back(clone_imu.first);
75  }
76 
77  // 1. Clean all feature measurements and make sure they all have valid clone times
78  auto it0 = feature_vec.begin();
79  while (it0 != feature_vec.end()) {
80 
81  // Clean the feature
82  (*it0)->clean_old_measurements(clonetimes);
83 
84  // Count how many measurements
85  int ct_meas = 0;
86  for (const auto &pair : (*it0)->timestamps) {
87  ct_meas += (*it0)->timestamps[pair.first].size();
88  }
89 
90  // Remove if we don't have enough
91  if (ct_meas < 2) {
92  (*it0)->to_delete = true;
93  it0 = feature_vec.erase(it0);
94  } else {
95  it0++;
96  }
97  }
98  rT1 = boost::posix_time::microsec_clock::local_time();
99 
100  // 2. Create vector of cloned *CAMERA* poses at each of our clone timesteps
101  std::unordered_map<size_t, std::unordered_map<double, FeatureInitializer::ClonePose>> clones_cam;
102  for (const auto &clone_calib : state->_calib_IMUtoCAM) {
103 
104  // For this camera, create the vector of camera poses
105  std::unordered_map<double, FeatureInitializer::ClonePose> clones_cami;
106  for (const auto &clone_imu : state->_clones_IMU) {
107 
108  // Get current camera pose
109  Eigen::Matrix<double, 3, 3> R_GtoCi = clone_calib.second->Rot() * clone_imu.second->Rot();
110  Eigen::Matrix<double, 3, 1> p_CioinG = clone_imu.second->pos() - R_GtoCi.transpose() * clone_calib.second->pos();
111 
112  // Append to our map
113  clones_cami.insert({clone_imu.first, FeatureInitializer::ClonePose(R_GtoCi, p_CioinG)});
114  }
115 
116  // Append to our map
117  clones_cam.insert({clone_calib.first, clones_cami});
118  }
119 
120  // 3. Try to triangulate all MSCKF or new SLAM features that have measurements
121  auto it1 = feature_vec.begin();
122  while (it1 != feature_vec.end()) {
123 
124  // Triangulate the feature and remove if it fails
125  bool success_tri = true;
126  if (initializer_feat->config().triangulate_1d) {
127  success_tri = initializer_feat->single_triangulation_1d(*it1, clones_cam);
128  } else {
129  success_tri = initializer_feat->single_triangulation(*it1, clones_cam);
130  }
131 
132  // Gauss-newton refine the feature
133  bool success_refine = true;
134  if (initializer_feat->config().refine_features) {
135  success_refine = initializer_feat->single_gaussnewton(*it1, clones_cam);
136  }
137 
138  // Remove the feature if not a success
139  if (!success_tri || !success_refine) {
140  (*it1)->to_delete = true;
141  it1 = feature_vec.erase(it1);
142  continue;
143  }
144  it1++;
145  }
146  rT2 = boost::posix_time::microsec_clock::local_time();
147 
148  // 4. Compute linear system for each feature, nullspace project, and reject
149  auto it2 = feature_vec.begin();
150  while (it2 != feature_vec.end()) {
151 
152  // Convert our feature into our current format
154  feat.featid = (*it2)->featid;
155  feat.uvs = (*it2)->uvs;
156  feat.uvs_norm = (*it2)->uvs_norm;
157  feat.timestamps = (*it2)->timestamps;
158 
159  // If we are using single inverse depth, then it is equivalent to using the msckf inverse depth
160  auto feat_rep =
161  ((int)feat.featid < state->_options.max_aruco_features) ? state->_options.feat_rep_aruco : state->_options.feat_rep_slam;
162  feat.feat_representation = feat_rep;
163  if (feat_rep == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
164  feat.feat_representation = LandmarkRepresentation::Representation::ANCHORED_MSCKF_INVERSE_DEPTH;
165  }
166 
167  // Save the position and its fej value
168  if (LandmarkRepresentation::is_relative_representation(feat.feat_representation)) {
169  feat.anchor_cam_id = (*it2)->anchor_cam_id;
170  feat.anchor_clone_timestamp = (*it2)->anchor_clone_timestamp;
171  feat.p_FinA = (*it2)->p_FinA;
172  feat.p_FinA_fej = (*it2)->p_FinA;
173  } else {
174  feat.p_FinG = (*it2)->p_FinG;
175  feat.p_FinG_fej = (*it2)->p_FinG;
176  }
177 
178  // Our return values (feature jacobian, state jacobian, residual, and order of state jacobian)
179  Eigen::MatrixXd H_f;
180  Eigen::MatrixXd H_x;
181  Eigen::VectorXd res;
182  std::vector<std::shared_ptr<Type>> Hx_order;
183 
184  // Get the Jacobian for this feature
185  UpdaterHelper::get_feature_jacobian_full(state, feat, H_f, H_x, res, Hx_order);
186 
187  // If we are doing the single feature representation, then we need to remove the bearing portion
188  // To do so, we project the bearing portion onto the state and depth Jacobians and the residual.
189  // This allows us to directly initialize the feature as a depth-old feature
190  if (feat_rep == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
191 
192  // Append the Jacobian in respect to the depth of the feature
193  Eigen::MatrixXd H_xf = H_x;
194  H_xf.conservativeResize(H_x.rows(), H_x.cols() + 1);
195  H_xf.block(0, H_x.cols(), H_x.rows(), 1) = H_f.block(0, H_f.cols() - 1, H_f.rows(), 1);
196  H_f.conservativeResize(H_f.rows(), H_f.cols() - 1);
197 
198  // Nullspace project the bearing portion
199  // This takes into account that we have marginalized the bearing already
200  // Thus this is crucial to ensuring estimator consistency as we are not taking the bearing to be true
202 
203  // Split out the state portion and feature portion
204  H_x = H_xf.block(0, 0, H_xf.rows(), H_xf.cols() - 1);
205  H_f = H_xf.block(0, H_xf.cols() - 1, H_xf.rows(), 1);
206  }
207 
208  // Create feature pointer (we will always create it of size three since we initialize the single invese depth as a msckf anchored
209  // representation)
210  int landmark_size = (feat_rep == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) ? 1 : 3;
211  auto landmark = std::make_shared<Landmark>(landmark_size);
212  landmark->_featid = feat.featid;
213  landmark->_feat_representation = feat_rep;
214  landmark->_unique_camera_id = (*it2)->anchor_cam_id;
215  if (LandmarkRepresentation::is_relative_representation(feat.feat_representation)) {
216  landmark->_anchor_cam_id = feat.anchor_cam_id;
217  landmark->_anchor_clone_timestamp = feat.anchor_clone_timestamp;
218  landmark->set_from_xyz(feat.p_FinA, false);
219  landmark->set_from_xyz(feat.p_FinA_fej, true);
220  } else {
221  landmark->set_from_xyz(feat.p_FinG, false);
222  landmark->set_from_xyz(feat.p_FinG_fej, true);
223  }
224 
225  // Measurement noise matrix
226  double sigma_pix_sq =
227  ((int)feat.featid < state->_options.max_aruco_features) ? _options_aruco.sigma_pix_sq : _options_slam.sigma_pix_sq;
228  Eigen::MatrixXd R = sigma_pix_sq * Eigen::MatrixXd::Identity(res.rows(), res.rows());
229 
230  // Try to initialize, delete new pointer if we failed
231  double chi2_multipler =
232  ((int)feat.featid < state->_options.max_aruco_features) ? _options_aruco.chi2_multipler : _options_slam.chi2_multipler;
233  if (StateHelper::initialize(state, landmark, Hx_order, H_x, H_f, R, res, chi2_multipler)) {
234  state->_features_SLAM.insert({(*it2)->featid, landmark});
235  (*it2)->to_delete = true;
236  it2++;
237  } else {
238  (*it2)->to_delete = true;
239  it2 = feature_vec.erase(it2);
240  }
241  }
242  rT3 = boost::posix_time::microsec_clock::local_time();
243 
244  // Debug print timing information
245  if (!feature_vec.empty()) {
246  PRINT_ALL("[SLAM-DELAY]: %.4f seconds to clean\n", (rT1 - rT0).total_microseconds() * 1e-6);
247  PRINT_ALL("[SLAM-DELAY]: %.4f seconds to triangulate\n", (rT2 - rT1).total_microseconds() * 1e-6);
248  PRINT_ALL("[SLAM-DELAY]: %.4f seconds initialize (%d features)\n", (rT3 - rT2).total_microseconds() * 1e-6, (int)feature_vec.size());
249  PRINT_ALL("[SLAM-DELAY]: %.4f seconds total\n", (rT3 - rT1).total_microseconds() * 1e-6);
250  }
251 }
252 
253 void UpdaterSLAM::update(std::shared_ptr<State> state, std::vector<std::shared_ptr<Feature>> &feature_vec) {
254 
255  // Return if no features
256  if (feature_vec.empty())
257  return;
258 
259  // Start timing
260  boost::posix_time::ptime rT0, rT1, rT2, rT3;
261  rT0 = boost::posix_time::microsec_clock::local_time();
262 
263  // 0. Get all timestamps our clones are at (and thus valid measurement times)
264  std::vector<double> clonetimes;
265  for (const auto &clone_imu : state->_clones_IMU) {
266  clonetimes.emplace_back(clone_imu.first);
267  }
268 
269  // 1. Clean all feature measurements and make sure they all have valid clone times
270  auto it0 = feature_vec.begin();
271  while (it0 != feature_vec.end()) {
272 
273  // Clean the feature
274  (*it0)->clean_old_measurements(clonetimes);
275 
276  // Count how many measurements
277  int ct_meas = 0;
278  for (const auto &pair : (*it0)->timestamps) {
279  ct_meas += (*it0)->timestamps[pair.first].size();
280  }
281 
282  // Get the landmark and its representation
283  // For single depth representation we need at least two measurement
284  // This is because we do nullspace projection
285  std::shared_ptr<Landmark> landmark = state->_features_SLAM.at((*it0)->featid);
286  int required_meas = (landmark->_feat_representation == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) ? 2 : 1;
287 
288  // Remove if we don't have enough
289  if (ct_meas < 1) {
290  (*it0)->to_delete = true;
291  it0 = feature_vec.erase(it0);
292  } else if (ct_meas < required_meas) {
293  it0 = feature_vec.erase(it0);
294  } else {
295  it0++;
296  }
297  }
298  rT1 = boost::posix_time::microsec_clock::local_time();
299 
300  // Calculate the max possible measurement size
301  size_t max_meas_size = 0;
302  for (size_t i = 0; i < feature_vec.size(); i++) {
303  for (const auto &pair : feature_vec.at(i)->timestamps) {
304  max_meas_size += 2 * feature_vec.at(i)->timestamps[pair.first].size();
305  }
306  }
307 
308  // Calculate max possible state size (i.e. the size of our covariance)
309  size_t max_hx_size = state->max_covariance_size();
310 
311  // Large Jacobian, residual, and measurement noise of *all* features for this update
312  Eigen::VectorXd res_big = Eigen::VectorXd::Zero(max_meas_size);
313  Eigen::MatrixXd Hx_big = Eigen::MatrixXd::Zero(max_meas_size, max_hx_size);
314  Eigen::MatrixXd R_big = Eigen::MatrixXd::Identity(max_meas_size, max_meas_size);
315  std::unordered_map<std::shared_ptr<Type>, size_t> Hx_mapping;
316  std::vector<std::shared_ptr<Type>> Hx_order_big;
317  size_t ct_jacob = 0;
318  size_t ct_meas = 0;
319 
320  // 4. Compute linear system for each feature, nullspace project, and reject
321  auto it2 = feature_vec.begin();
322  while (it2 != feature_vec.end()) {
323 
324  // Ensure we have the landmark and it is the same
325  assert(state->_features_SLAM.find((*it2)->featid) != state->_features_SLAM.end());
326  assert(state->_features_SLAM.at((*it2)->featid)->_featid == (*it2)->featid);
327 
328  // Get our landmark from the state
329  std::shared_ptr<Landmark> landmark = state->_features_SLAM.at((*it2)->featid);
330 
331  // Convert the state landmark into our current format
333  feat.featid = (*it2)->featid;
334  feat.uvs = (*it2)->uvs;
335  feat.uvs_norm = (*it2)->uvs_norm;
336  feat.timestamps = (*it2)->timestamps;
337 
338  // If we are using single inverse depth, then it is equivalent to using the msckf inverse depth
339  feat.feat_representation = landmark->_feat_representation;
340  if (landmark->_feat_representation == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
341  feat.feat_representation = LandmarkRepresentation::Representation::ANCHORED_MSCKF_INVERSE_DEPTH;
342  }
343 
344  // Save the position and its fej value
345  if (LandmarkRepresentation::is_relative_representation(feat.feat_representation)) {
346  feat.anchor_cam_id = landmark->_anchor_cam_id;
347  feat.anchor_clone_timestamp = landmark->_anchor_clone_timestamp;
348  feat.p_FinA = landmark->get_xyz(false);
349  feat.p_FinA_fej = landmark->get_xyz(true);
350  } else {
351  feat.p_FinG = landmark->get_xyz(false);
352  feat.p_FinG_fej = landmark->get_xyz(true);
353  }
354 
355  // Our return values (feature jacobian, state jacobian, residual, and order of state jacobian)
356  Eigen::MatrixXd H_f;
357  Eigen::MatrixXd H_x;
358  Eigen::VectorXd res;
359  std::vector<std::shared_ptr<Type>> Hx_order;
360 
361  // Get the Jacobian for this feature
362  UpdaterHelper::get_feature_jacobian_full(state, feat, H_f, H_x, res, Hx_order);
363 
364  // Place Jacobians in one big Jacobian, since the landmark is already in our state vector
365  Eigen::MatrixXd H_xf = H_x;
366  if (landmark->_feat_representation == LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) {
367 
368  // Append the Jacobian in respect to the depth of the feature
369  H_xf.conservativeResize(H_x.rows(), H_x.cols() + 1);
370  H_xf.block(0, H_x.cols(), H_x.rows(), 1) = H_f.block(0, H_f.cols() - 1, H_f.rows(), 1);
371  H_f.conservativeResize(H_f.rows(), H_f.cols() - 1);
372 
373  // Nullspace project the bearing portion
374  // This takes into account that we have marginalized the bearing already
375  // Thus this is crucial to ensuring estimator consistency as we are not taking the bearing to be true
377 
378  } else {
379 
380  // Else we have the full feature in our state, so just append it
381  H_xf.conservativeResize(H_x.rows(), H_x.cols() + H_f.cols());
382  H_xf.block(0, H_x.cols(), H_x.rows(), H_f.cols()) = H_f;
383  }
384 
385  // Append to our Jacobian order vector
386  std::vector<std::shared_ptr<Type>> Hxf_order = Hx_order;
387  Hxf_order.push_back(landmark);
388 
389  // Chi2 distance check
390  Eigen::MatrixXd P_marg = StateHelper::get_marginal_covariance(state, Hxf_order);
391  Eigen::MatrixXd S = H_xf * P_marg * H_xf.transpose();
392  double sigma_pix_sq =
393  ((int)feat.featid < state->_options.max_aruco_features) ? _options_aruco.sigma_pix_sq : _options_slam.sigma_pix_sq;
394  S.diagonal() += sigma_pix_sq * Eigen::VectorXd::Ones(S.rows());
395  double chi2 = res.dot(S.llt().solve(res));
396 
397  // Get our threshold (we precompute up to 500 but handle the case that it is more)
398  double chi2_check;
399  if (res.rows() < 500) {
400  chi2_check = chi_squared_table[res.rows()];
401  } else {
402  boost::math::chi_squared chi_squared_dist(res.rows());
403  chi2_check = boost::math::quantile(chi_squared_dist, 0.95);
404  PRINT_WARNING(YELLOW "chi2_check over the residual limit - %d\n" RESET, (int)res.rows());
405  }
406 
407  // Check if we should delete or not
408  double chi2_multipler =
409  ((int)feat.featid < state->_options.max_aruco_features) ? _options_aruco.chi2_multipler : _options_slam.chi2_multipler;
410  if (chi2 > chi2_multipler * chi2_check) {
411  if ((int)feat.featid < state->_options.max_aruco_features) {
412  PRINT_WARNING(YELLOW "[SLAM-UP]: rejecting aruco tag %d for chi2 thresh (%.3f > %.3f)\n" RESET, (int)feat.featid, chi2,
413  chi2_multipler * chi2_check);
414  } else {
415  landmark->update_fail_count++;
416  }
417  (*it2)->to_delete = true;
418  it2 = feature_vec.erase(it2);
419  continue;
420  }
421 
422  // Debug print when we are going to update the aruco tags
423  if ((int)feat.featid < state->_options.max_aruco_features) {
424  PRINT_DEBUG("[SLAM-UP]: accepted aruco tag %d for chi2 thresh (%.3f < %.3f)\n", (int)feat.featid, chi2, chi2_multipler * chi2_check);
425  }
426 
427  // We are good!!! Append to our large H vector
428  size_t ct_hx = 0;
429  for (const auto &var : Hxf_order) {
430 
431  // Ensure that this variable is in our Jacobian
432  if (Hx_mapping.find(var) == Hx_mapping.end()) {
433  Hx_mapping.insert({var, ct_jacob});
434  Hx_order_big.push_back(var);
435  ct_jacob += var->size();
436  }
437 
438  // Append to our large Jacobian
439  Hx_big.block(ct_meas, Hx_mapping[var], H_xf.rows(), var->size()) = H_xf.block(0, ct_hx, H_xf.rows(), var->size());
440  ct_hx += var->size();
441  }
442 
443  // Our isotropic measurement noise
444  R_big.block(ct_meas, ct_meas, res.rows(), res.rows()) *= sigma_pix_sq;
445 
446  // Append our residual and move forward
447  res_big.block(ct_meas, 0, res.rows(), 1) = res;
448  ct_meas += res.rows();
449  it2++;
450  }
451  rT2 = boost::posix_time::microsec_clock::local_time();
452 
453  // We have appended all features to our Hx_big, res_big
454  // Delete it so we do not reuse information
455  for (size_t f = 0; f < feature_vec.size(); f++) {
456  feature_vec[f]->to_delete = true;
457  }
458 
459  // Return if we don't have anything and resize our matrices
460  if (ct_meas < 1) {
461  return;
462  }
463  assert(ct_meas <= max_meas_size);
464  assert(ct_jacob <= max_hx_size);
465  res_big.conservativeResize(ct_meas, 1);
466  Hx_big.conservativeResize(ct_meas, ct_jacob);
467  R_big.conservativeResize(ct_meas, ct_meas);
468 
469  // 5. With all good SLAM features update the state
470  StateHelper::EKFUpdate(state, Hx_order_big, Hx_big, res_big, R_big);
471  rT3 = boost::posix_time::microsec_clock::local_time();
472 
473  // Debug print timing information
474  PRINT_ALL("[SLAM-UP]: %.4f seconds to clean\n", (rT1 - rT0).total_microseconds() * 1e-6);
475  PRINT_ALL("[SLAM-UP]: %.4f seconds creating linear system\n", (rT2 - rT1).total_microseconds() * 1e-6);
476  PRINT_ALL("[SLAM-UP]: %.4f seconds to update (%d feats of %d size)\n", (rT3 - rT2).total_microseconds() * 1e-6, (int)feature_vec.size(),
477  (int)Hx_big.rows());
478  PRINT_ALL("[SLAM-UP]: %.4f seconds total\n", (rT3 - rT1).total_microseconds() * 1e-6);
479 }
480 
481 void UpdaterSLAM::change_anchors(std::shared_ptr<State> state) {
482 
483  // Return if we do not have enough clones
484  if ((int)state->_clones_IMU.size() <= state->_options.max_clone_size) {
485  return;
486  }
487 
488  // Get the marginalization timestep, and change the anchor for any feature seen from it
489  // NOTE: for now we have anchor the feature in the same camera as it is before
490  // NOTE: this also does not change the representation of the feature at all right now
491  double marg_timestep = state->margtimestep();
492  for (auto &f : state->_features_SLAM) {
493  // Skip any features that are in the global frame
494  if (f.second->_feat_representation == LandmarkRepresentation::Representation::GLOBAL_3D ||
495  f.second->_feat_representation == LandmarkRepresentation::Representation::GLOBAL_FULL_INVERSE_DEPTH)
496  continue;
497  // Else lets see if it is anchored in the clone that will be marginalized
498  assert(marg_timestep <= f.second->_anchor_clone_timestamp);
499  if (f.second->_anchor_clone_timestamp == marg_timestep) {
500  perform_anchor_change(state, f.second, state->_timestamp, f.second->_anchor_cam_id);
501  }
502  }
503 }
504 
505 void UpdaterSLAM::perform_anchor_change(std::shared_ptr<State> state, std::shared_ptr<Landmark> landmark, double new_anchor_timestamp,
506  size_t new_cam_id) {
507 
508  // Assert that this is an anchored representation
509  assert(LandmarkRepresentation::is_relative_representation(landmark->_feat_representation));
510  assert(landmark->_anchor_cam_id != -1);
511 
512  // Create current feature representation
514  old_feat.featid = landmark->_featid;
515  old_feat.feat_representation = landmark->_feat_representation;
516  old_feat.anchor_cam_id = landmark->_anchor_cam_id;
517  old_feat.anchor_clone_timestamp = landmark->_anchor_clone_timestamp;
518  old_feat.p_FinA = landmark->get_xyz(false);
519  old_feat.p_FinA_fej = landmark->get_xyz(true);
520 
521  // Get Jacobians of p_FinG wrt old representation
522  Eigen::MatrixXd H_f_old;
523  std::vector<Eigen::MatrixXd> H_x_old;
524  std::vector<std::shared_ptr<Type>> x_order_old;
525  UpdaterHelper::get_feature_jacobian_representation(state, old_feat, H_f_old, H_x_old, x_order_old);
526 
527  // Create future feature representation
529  new_feat.featid = landmark->_featid;
530  new_feat.feat_representation = landmark->_feat_representation;
531  new_feat.anchor_cam_id = new_cam_id;
532  new_feat.anchor_clone_timestamp = new_anchor_timestamp;
533 
534  //==========================================================================
535  //==========================================================================
536 
537  // OLD: anchor camera position and orientation
538  Eigen::Matrix<double, 3, 3> R_GtoIOLD = state->_clones_IMU.at(old_feat.anchor_clone_timestamp)->Rot();
539  Eigen::Matrix<double, 3, 3> R_GtoOLD = state->_calib_IMUtoCAM.at(old_feat.anchor_cam_id)->Rot() * R_GtoIOLD;
540  Eigen::Matrix<double, 3, 1> p_OLDinG = state->_clones_IMU.at(old_feat.anchor_clone_timestamp)->pos() -
541  R_GtoOLD.transpose() * state->_calib_IMUtoCAM.at(old_feat.anchor_cam_id)->pos();
542 
543  // NEW: anchor camera position and orientation
544  Eigen::Matrix<double, 3, 3> R_GtoINEW = state->_clones_IMU.at(new_feat.anchor_clone_timestamp)->Rot();
545  Eigen::Matrix<double, 3, 3> R_GtoNEW = state->_calib_IMUtoCAM.at(new_feat.anchor_cam_id)->Rot() * R_GtoINEW;
546  Eigen::Matrix<double, 3, 1> p_NEWinG = state->_clones_IMU.at(new_feat.anchor_clone_timestamp)->pos() -
547  R_GtoNEW.transpose() * state->_calib_IMUtoCAM.at(new_feat.anchor_cam_id)->pos();
548 
549  // Calculate transform between the old anchor and new one
550  Eigen::Matrix<double, 3, 3> R_OLDtoNEW = R_GtoNEW * R_GtoOLD.transpose();
551  Eigen::Matrix<double, 3, 1> p_OLDinNEW = R_GtoNEW * (p_OLDinG - p_NEWinG);
552  new_feat.p_FinA = R_OLDtoNEW * landmark->get_xyz(false) + p_OLDinNEW;
553 
554  //==========================================================================
555  //==========================================================================
556 
557  // OLD: anchor camera position and orientation
558  Eigen::Matrix<double, 3, 3> R_GtoIOLD_fej = state->_clones_IMU.at(old_feat.anchor_clone_timestamp)->Rot_fej();
559  Eigen::Matrix<double, 3, 3> R_GtoOLD_fej = state->_calib_IMUtoCAM.at(old_feat.anchor_cam_id)->Rot() * R_GtoIOLD_fej;
560  Eigen::Matrix<double, 3, 1> p_OLDinG_fej = state->_clones_IMU.at(old_feat.anchor_clone_timestamp)->pos_fej() -
561  R_GtoOLD_fej.transpose() * state->_calib_IMUtoCAM.at(old_feat.anchor_cam_id)->pos();
562 
563  // NEW: anchor camera position and orientation
564  Eigen::Matrix<double, 3, 3> R_GtoINEW_fej = state->_clones_IMU.at(new_feat.anchor_clone_timestamp)->Rot_fej();
565  Eigen::Matrix<double, 3, 3> R_GtoNEW_fej = state->_calib_IMUtoCAM.at(new_feat.anchor_cam_id)->Rot() * R_GtoINEW_fej;
566  Eigen::Matrix<double, 3, 1> p_NEWinG_fej = state->_clones_IMU.at(new_feat.anchor_clone_timestamp)->pos_fej() -
567  R_GtoNEW_fej.transpose() * state->_calib_IMUtoCAM.at(new_feat.anchor_cam_id)->pos();
568 
569  // Calculate transform between the old anchor and new one
570  Eigen::Matrix<double, 3, 3> R_OLDtoNEW_fej = R_GtoNEW_fej * R_GtoOLD_fej.transpose();
571  Eigen::Matrix<double, 3, 1> p_OLDinNEW_fej = R_GtoNEW_fej * (p_OLDinG_fej - p_NEWinG_fej);
572  new_feat.p_FinA_fej = R_OLDtoNEW_fej * landmark->get_xyz(true) + p_OLDinNEW_fej;
573 
574  // Get Jacobians of p_FinG wrt new representation
575  Eigen::MatrixXd H_f_new;
576  std::vector<Eigen::MatrixXd> H_x_new;
577  std::vector<std::shared_ptr<Type>> x_order_new;
578  UpdaterHelper::get_feature_jacobian_representation(state, new_feat, H_f_new, H_x_new, x_order_new);
579 
580  //==========================================================================
581  //==========================================================================
582 
583  // New phi order is just the landmark
584  std::vector<std::shared_ptr<Type>> phi_order_NEW;
585  phi_order_NEW.push_back(landmark);
586 
587  // Loop through all our orders and append them
588  std::vector<std::shared_ptr<Type>> phi_order_OLD;
589  int current_it = 0;
590  std::map<std::shared_ptr<Type>, int> Phi_id_map;
591  for (const auto &var : x_order_old) {
592  if (Phi_id_map.find(var) == Phi_id_map.end()) {
593  Phi_id_map.insert({var, current_it});
594  phi_order_OLD.push_back(var);
595  current_it += var->size();
596  }
597  }
598  for (const auto &var : x_order_new) {
599  if (Phi_id_map.find(var) == Phi_id_map.end()) {
600  Phi_id_map.insert({var, current_it});
601  phi_order_OLD.push_back(var);
602  current_it += var->size();
603  }
604  }
605  Phi_id_map.insert({landmark, current_it});
606  phi_order_OLD.push_back(landmark);
607  current_it += landmark->size();
608 
609  // Anchor change Jacobian
610  int phisize = (new_feat.feat_representation != LandmarkRepresentation::Representation::ANCHORED_INVERSE_DEPTH_SINGLE) ? 3 : 1;
611  Eigen::MatrixXd Phi = Eigen::MatrixXd::Zero(phisize, current_it);
612  Eigen::MatrixXd Q = Eigen::MatrixXd::Zero(phisize, phisize);
613 
614  // Inverse of our new representation
615  // pf_new_error = Hfnew^{-1}*(Hfold*pf_olderror+Hxold*x_olderror-Hxnew*x_newerror)
616  Eigen::MatrixXd H_f_new_inv;
617  if (phisize == 1) {
618  H_f_new_inv = 1.0 / H_f_new.squaredNorm() * H_f_new.transpose();
619  } else {
620  H_f_new_inv = H_f_new.colPivHouseholderQr().solve(Eigen::Matrix<double, 3, 3>::Identity());
621  }
622 
623  // Place Jacobians for old anchor
624  for (size_t i = 0; i < H_x_old.size(); i++) {
625  Phi.block(0, Phi_id_map.at(x_order_old[i]), phisize, x_order_old[i]->size()).noalias() += H_f_new_inv * H_x_old[i];
626  }
627 
628  // Place Jacobians for old feat
629  Phi.block(0, Phi_id_map.at(landmark), phisize, phisize) = H_f_new_inv * H_f_old;
630 
631  // Place Jacobians for new anchor
632  for (size_t i = 0; i < H_x_new.size(); i++) {
633  Phi.block(0, Phi_id_map.at(x_order_new[i]), phisize, x_order_new[i]->size()).noalias() -= H_f_new_inv * H_x_new[i];
634  }
635 
636  // Perform covariance propagation
637  StateHelper::EKFPropagation(state, phi_order_NEW, phi_order_OLD, Phi, Q);
638 
639  // Set state from new feature
640  landmark->_featid = new_feat.featid;
641  landmark->_feat_representation = new_feat.feat_representation;
642  landmark->_anchor_cam_id = new_feat.anchor_cam_id;
643  landmark->_anchor_clone_timestamp = new_feat.anchor_clone_timestamp;
644  landmark->set_from_xyz(new_feat.p_FinA, false);
645  landmark->set_from_xyz(new_feat.p_FinA_fej, true);
646  landmark->has_had_anchor_change = true;
647 }
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::UpdaterSLAM::delayed_init
void delayed_init(std::shared_ptr< State > state, std::vector< std::shared_ptr< ov_core::Feature >> &feature_vec)
Given max track features, this will try to use them to initialize them in the state.
Definition: UpdaterSLAM.cpp:61
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::UpdaterSLAM::initializer_feat
std::shared_ptr< ov_core::FeatureInitializer > initializer_feat
Feature initializer class object.
Definition: UpdaterSLAM.h:107
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::UpdaterSLAM::chi_squared_table
std::map< int, double > chi_squared_table
Chi squared 95th percentile table (lookup would be size of residual)
Definition: UpdaterSLAM.h:110
quat_ops.h
UpdaterSLAM.h
UpdaterHelper.h
ov_msckf::UpdaterOptions
Struct which stores general updater options.
Definition: UpdaterOptions.h:32
LandmarkRepresentation.h
ov_msckf::UpdaterHelper::get_feature_jacobian_representation
static void get_feature_jacobian_representation(std::shared_ptr< State > state, UpdaterHelperFeature &feature, Eigen::MatrixXd &H_f, std::vector< Eigen::MatrixXd > &H_x, std::vector< std::shared_ptr< ov_type::Type >> &x_order)
This gets the feature and state Jacobian in respect to the feature representation.
Definition: UpdaterHelper.cpp:32
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
PRINT_DEBUG
#define PRINT_DEBUG(x...)
FeatureInitializer.h
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::StateHelper::initialize
static bool initialize(std::shared_ptr< State > state, std::shared_ptr< ov_type::Type > new_variable, const std::vector< std::shared_ptr< ov_type::Type >> &H_order, Eigen::MatrixXd &H_R, Eigen::MatrixXd &H_L, Eigen::MatrixXd &R, Eigen::VectorXd &res, double chi_2_mult)
Initializes new variable into covariance.
Definition: StateHelper.cpp:393
ov_msckf::UpdaterSLAM::update
void update(std::shared_ptr< State > state, std::vector< std::shared_ptr< ov_core::Feature >> &feature_vec)
Given tracked SLAM features, this will try to use them to update the state.
Definition: UpdaterSLAM.cpp:253
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::UpdaterHelper::UpdaterHelperFeature::feat_representation
ov_type::LandmarkRepresentation::Representation feat_representation
What representation our feature is in.
Definition: UpdaterHelper.h:69
ov_msckf::UpdaterSLAM::_options_aruco
UpdaterOptions _options_aruco
Options used during update for aruco features.
Definition: UpdaterSLAM.h:104
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::UpdaterHelperFeature::p_FinG
Eigen::Vector3d p_FinG
Triangulated position of this feature, in the global frame.
Definition: UpdaterHelper.h:84
ov_msckf::UpdaterSLAM::change_anchors
void change_anchors(std::shared_ptr< State > state)
Will change SLAM feature anchors if it will be marginalized.
Definition: UpdaterSLAM.cpp:481
ov_msckf::UpdaterSLAM::perform_anchor_change
void perform_anchor_change(std::shared_ptr< State > state, std::shared_ptr< ov_type::Landmark > landmark, double new_anchor_timestamp, size_t new_cam_id)
Shifts landmark anchor to new clone.
Definition: UpdaterSLAM.cpp:505
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::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
ov_msckf::UpdaterSLAM::_options_slam
UpdaterOptions _options_slam
Options used during update for slam features.
Definition: UpdaterSLAM.h:101
clonetimes
std::deque< double > clonetimes
print.h
colors.h
Landmark.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::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
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