UpdaterZeroVelocity.h
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 #ifndef OV_MSCKF_UPDATER_ZEROVELOCITY_H
23 #define OV_MSCKF_UPDATER_ZEROVELOCITY_H
24 
25 #include <memory>
26 
27 #include "utils/sensor_data.h"
28 
29 #include "UpdaterOptions.h"
30 #include "utils/NoiseManager.h"
31 
32 namespace ov_core {
33 class Feature;
34 class FeatureDatabase;
35 } // namespace ov_core
36 namespace ov_type {
37 class Landmark;
38 } // namespace ov_type
39 
40 namespace ov_msckf {
41 
42 class State;
43 class Propagator;
44 
55 
56 public:
68  UpdaterZeroVelocity(UpdaterOptions &options, NoiseManager &noises, std::shared_ptr<ov_core::FeatureDatabase> db,
69  std::shared_ptr<Propagator> prop, double gravity_mag, double zupt_max_velocity, double zupt_noise_multiplier,
70  double zupt_max_disparity);
71 
77  void feed_imu(const ov_core::ImuData &message, double oldest_time = -1) {
78 
79  // Append it to our vector
80  imu_data.emplace_back(message);
81 
82  // Sort our imu data (handles any out of order measurements)
83  // std::sort(imu_data.begin(), imu_data.end(), [](const IMUDATA i, const IMUDATA j) {
84  // return i.timestamp < j.timestamp;
85  //});
86 
87  // Clean old measurements
88  // std::cout << "ZVUPT: imu_data.size() " << imu_data.size() << std::endl;
89  clean_old_imu_measurements(oldest_time - 0.10);
90  }
91 
96  void clean_old_imu_measurements(double oldest_time) {
97  if (oldest_time < 0)
98  return;
99  auto it0 = imu_data.begin();
100  while (it0 != imu_data.end()) {
101  if (it0->timestamp < oldest_time) {
102  it0 = imu_data.erase(it0);
103  } else {
104  it0++;
105  }
106  }
107  }
108 
115  bool try_update(std::shared_ptr<State> state, double timestamp);
116 
117 protected:
120 
123 
125  std::shared_ptr<ov_core::FeatureDatabase> _db;
126 
128  std::shared_ptr<Propagator> _prop;
129 
131  Eigen::Vector3d _gravity;
132 
134  double _zupt_max_velocity = 1.0;
135 
138 
140  double _zupt_max_disparity = 1.0;
141 
143  std::map<int, double> chi_squared_table;
144 
146  std::vector<ov_core::ImuData> imu_data;
147 
149  double last_prop_time_offset = 0.0;
151 
154 
157 };
158 
159 } // namespace ov_msckf
160 
161 #endif // OV_MSCKF_UPDATER_ZEROVELOCITY_H
ov_msckf::UpdaterZeroVelocity::_db
std::shared_ptr< ov_core::FeatureDatabase > _db
Feature tracker database with all features in it.
Definition: UpdaterZeroVelocity.h:125
ov_msckf::UpdaterZeroVelocity::have_last_prop_time_offset
bool have_last_prop_time_offset
Definition: UpdaterZeroVelocity.h:150
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::UpdaterZeroVelocity::last_zupt_state_timestamp
double last_zupt_state_timestamp
Last timestamp we did zero velocity update with.
Definition: UpdaterZeroVelocity.h:153
ov_msckf::UpdaterOptions
Struct which stores general updater options.
Definition: UpdaterOptions.h:32
ov_msckf::UpdaterZeroVelocity::UpdaterZeroVelocity
UpdaterZeroVelocity(UpdaterOptions &options, NoiseManager &noises, std::shared_ptr< ov_core::FeatureDatabase > db, std::shared_ptr< Propagator > prop, double gravity_mag, double zupt_max_velocity, double zupt_noise_multiplier, double zupt_max_disparity)
Default constructor for our zero velocity detector and updater.
Definition: UpdaterZeroVelocity.cpp:42
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
sensor_data.h
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
ov_msckf::UpdaterZeroVelocity::feed_imu
void feed_imu(const ov_core::ImuData &message, double oldest_time=-1)
Feed function for inertial data.
Definition: UpdaterZeroVelocity.h:77
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::UpdaterZeroVelocity::clean_old_imu_measurements
void clean_old_imu_measurements(double oldest_time)
This will remove any IMU measurements that are older then the given measurement time.
Definition: UpdaterZeroVelocity.h:96
ov_core::ImuData
ov_msckf::UpdaterZeroVelocity
Will try to detect and then update using zero velocity assumption.
Definition: UpdaterZeroVelocity.h:54
ov_type
NoiseManager.h
ov_msckf::UpdaterZeroVelocity::_options
UpdaterOptions _options
Options used during update (chi2 multiplier)
Definition: UpdaterZeroVelocity.h:119
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
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
UpdaterOptions.h
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


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