Simulator.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_SIMULATOR_H
23 #define OV_MSCKF_SIMULATOR_H
24 
25 #include <Eigen/Eigen>
26 #include <fstream>
27 #include <opencv2/core/core.hpp>
28 #include <random>
29 #include <sstream>
30 #include <string>
31 #include <unordered_map>
32 
33 #include "core/VioManagerOptions.h"
34 
35 namespace ov_core {
36 class BsplineSE3;
37 } // namespace ov_core
38 
39 namespace ov_msckf {
40 
52 class Simulator {
53 
54 public:
59  Simulator(VioManagerOptions &params_);
60 
66  static void perturb_parameters(std::mt19937 gen_state, VioManagerOptions &params_);
67 
72  bool ok() { return is_running; }
73 
78  double current_timestamp() { return timestamp; }
79 
86  bool get_state(double desired_time, Eigen::Matrix<double, 17, 1> &imustate);
87 
95  bool get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am);
96 
104  bool get_next_cam(double &time_cam, std::vector<int> &camids, std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats);
105 
107  std::unordered_map<size_t, Eigen::Vector3d> get_map() { return featmap; }
108 
110  std::vector<Eigen::Vector3d> get_map_vec() {
111  std::vector<Eigen::Vector3d> feats;
112  for (auto const &feat : featmap)
113  feats.push_back(feat.second);
114  return feats;
115  }
116 
119 
120 protected:
129  std::vector<std::pair<size_t, Eigen::VectorXf>> project_pointcloud(const Eigen::Matrix3d &R_GtoI, const Eigen::Vector3d &p_IinG,
130  int camid, const std::unordered_map<size_t, Eigen::Vector3d> &feats);
131 
140  void generate_points(const Eigen::Matrix3d &R_GtoI, const Eigen::Vector3d &p_IinG, int camid,
141  std::unordered_map<size_t, Eigen::Vector3d> &feats, int numpts);
142 
143  //===================================================================
144  // Configuration variables
145  //===================================================================
146 
149 
150  //===================================================================
151  // State related variables
152  //===================================================================
153 
155  std::vector<Eigen::VectorXd> traj_data;
156 
158  std::shared_ptr<ov_core::BsplineSE3> spline;
159 
161  size_t id_map = 0;
162  std::unordered_map<size_t, Eigen::Vector3d> featmap;
163 
165  std::mt19937 gen_meas_imu;
166 
168  std::vector<std::mt19937> gen_meas_cams;
169 
171  std::mt19937 gen_state_init;
172 
174  std::mt19937 gen_state_perturb;
175 
178 
179  //===================================================================
180  // Simulation specific variables
181  //===================================================================
182 
184  double timestamp;
185 
188 
191 
193  Eigen::Vector3d true_bias_accel = Eigen::Vector3d::Zero();
194 
196  Eigen::Vector3d true_bias_gyro = Eigen::Vector3d::Zero();
197 
198  // Our history of true biases
200  std::vector<double> hist_true_bias_time;
201  std::vector<Eigen::Vector3d> hist_true_bias_accel;
202  std::vector<Eigen::Vector3d> hist_true_bias_gyro;
203 };
204 
205 } // namespace ov_msckf
206 
207 #endif // OV_MSCKF_SIMULATOR_H
ov_msckf::Simulator::featmap
std::unordered_map< size_t, Eigen::Vector3d > featmap
Definition: Simulator.h:162
ov_msckf::Simulator::get_state
bool get_state(double desired_time, Eigen::Matrix< double, 17, 1 > &imustate)
Get the simulation state at a specified timestep.
Definition: Simulator.cpp:267
ov_msckf::Simulator::is_running
bool is_running
If our simulation is running.
Definition: Simulator.h:177
ov_msckf::Simulator::timestamp
double timestamp
Current timestamp of the system.
Definition: Simulator.h:184
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::Simulator::params
VioManagerOptions params
True vio manager params (a copy of the parsed ones)
Definition: Simulator.h:148
ov_msckf::Simulator::timestamp_last_cam
double timestamp_last_cam
Last time we had an CAMERA reading.
Definition: Simulator.h:190
ov_msckf::Simulator::get_next_cam
bool get_next_cam(double &time_cam, std::vector< int > &camids, std::vector< std::vector< std::pair< size_t, Eigen::VectorXf >>> &feats)
Gets the next inertial reading if we have one.
Definition: Simulator.cpp:391
ov_msckf::Simulator::hist_true_bias_gyro
std::vector< Eigen::Vector3d > hist_true_bias_gyro
Definition: Simulator.h:202
ov_msckf::Simulator::get_map
std::unordered_map< size_t, Eigen::Vector3d > get_map()
Returns the true 3d map of features.
Definition: Simulator.h:107
ov_msckf::Simulator::spline
std::shared_ptr< ov_core::BsplineSE3 > spline
Our b-spline trajectory.
Definition: Simulator.h:158
ov_msckf::Simulator::get_map_vec
std::vector< Eigen::Vector3d > get_map_vec()
Returns the true 3d map of features.
Definition: Simulator.h:110
ov_msckf::Simulator::current_timestamp
double current_timestamp()
Gets the timestamp we have simulated up too.
Definition: Simulator.h:78
ov_msckf::Simulator::hist_true_bias_time
std::vector< double > hist_true_bias_time
Definition: Simulator.h:200
ov_msckf::Simulator::hist_true_bias_accel
std::vector< Eigen::Vector3d > hist_true_bias_accel
Definition: Simulator.h:201
ov_msckf::Simulator::true_bias_gyro
Eigen::Vector3d true_bias_gyro
Our running gyroscope bias.
Definition: Simulator.h:196
ov_msckf::Simulator::generate_points
void generate_points(const Eigen::Matrix3d &R_GtoI, const Eigen::Vector3d &p_IinG, int camid, std::unordered_map< size_t, Eigen::Vector3d > &feats, int numpts)
Will generate points in the fov of the specified camera.
Definition: Simulator.cpp:501
ov_msckf::Simulator::project_pointcloud
std::vector< std::pair< size_t, Eigen::VectorXf > > project_pointcloud(const Eigen::Matrix3d &R_GtoI, const Eigen::Vector3d &p_IinG, int camid, const std::unordered_map< size_t, Eigen::Vector3d > &feats)
Projects the passed map features into the desired camera frame.
Definition: Simulator.cpp:453
VioManagerOptions.h
ov_msckf::Simulator::true_bias_accel
Eigen::Vector3d true_bias_accel
Our running acceleration bias.
Definition: Simulator.h:193
ov_msckf::Simulator::gen_meas_cams
std::vector< std::mt19937 > gen_meas_cams
Mersenne twister PRNG for measurements (CAMERAS)
Definition: Simulator.h:168
ov_msckf::Simulator::has_skipped_first_bias
bool has_skipped_first_bias
Definition: Simulator.h:199
ov_msckf::Simulator::gen_state_init
std::mt19937 gen_state_init
Mersenne twister PRNG for state initialization.
Definition: Simulator.h:171
ov_msckf::Simulator::id_map
size_t id_map
Our map of 3d features.
Definition: Simulator.h:161
ov_msckf::Simulator::perturb_parameters
static void perturb_parameters(std::mt19937 gen_state, VioManagerOptions &params_)
Will get a set of perturbed parameters.
Definition: Simulator.cpp:209
ov_msckf::Simulator::Simulator
Simulator(VioManagerOptions &params_)
Default constructor, will load all configuration variables.
Definition: Simulator.cpp:35
ov_msckf::Simulator::traj_data
std::vector< Eigen::VectorXd > traj_data
Our loaded trajectory data (timestamp(s), q_GtoI, p_IinG)
Definition: Simulator.h:155
ov_msckf::VioManagerOptions
Struct which stores all options needed for state estimation.
Definition: VioManagerOptions.h:56
ov_msckf::Simulator::gen_state_perturb
std::mt19937 gen_state_perturb
Mersenne twister PRNG for state perturbations.
Definition: Simulator.h:174
ov_msckf::Simulator::get_true_parameters
VioManagerOptions get_true_parameters()
Access function to get the true parameters (i.e. calibration and settings)
Definition: Simulator.h:118
ov_msckf::Simulator::timestamp_last_imu
double timestamp_last_imu
Last time we had an IMU reading.
Definition: Simulator.h:187
ov_msckf::Simulator::get_next_imu
bool get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am)
Gets the next inertial reading if we have one.
Definition: Simulator.cpp:311
ov_core
ov_msckf::Simulator
Master simulator class that generated visual-inertial measurements.
Definition: Simulator.h:52
ov_msckf::Simulator::ok
bool ok()
Returns if we are actively simulating.
Definition: Simulator.h:72
ov_msckf::Simulator::gen_meas_imu
std::mt19937 gen_meas_imu
Mersenne twister PRNG for measurements (IMU)
Definition: Simulator.h:165


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