SimulatorInit.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_INIT_SIMULATORINIT_H
23 #define OV_INIT_SIMULATORINIT_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 
34 
35 namespace ov_core {
36 class BsplineSE3;
37 } // namespace ov_core
38 
39 namespace ov_init {
40 
53 
54 public:
60 
65  void perturb_parameters(InertialInitializerOptions &params_);
66 
71  bool ok() { return is_running; }
72 
77  double current_timestamp() { return timestamp; }
78 
85  bool get_state(double desired_time, Eigen::Matrix<double, 17, 1> &imustate);
86 
94  bool get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am);
95 
103  bool get_next_cam(double &time_cam, std::vector<int> &camids, std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats);
104 
106  std::unordered_map<size_t, Eigen::Vector3d> get_map() { return featmap; }
107 
110 
111 protected:
120  std::vector<std::pair<size_t, Eigen::VectorXf>> project_pointcloud(const Eigen::Matrix3d &R_GtoI, const Eigen::Vector3d &p_IinG,
121  int camid, const std::unordered_map<size_t, Eigen::Vector3d> &feats);
122 
131  void generate_points(const Eigen::Matrix3d &R_GtoI, const Eigen::Vector3d &p_IinG, int camid,
132  std::unordered_map<size_t, Eigen::Vector3d> &feats, int numpts);
133 
134  //===================================================================
135  // Configuration variables
136  //===================================================================
137 
140 
141  //===================================================================
142  // State related variables
143  //===================================================================
144 
146  std::vector<Eigen::VectorXd> traj_data;
147 
149  std::shared_ptr<ov_core::BsplineSE3> spline;
150 
152  size_t id_map = 0;
153  std::unordered_map<size_t, Eigen::Vector3d> featmap;
154 
156  std::mt19937 gen_meas_imu;
157 
159  std::vector<std::mt19937> gen_meas_cams;
160 
162  std::mt19937 gen_state_init;
163 
165  std::mt19937 gen_state_perturb;
166 
169 
170  //===================================================================
171  // Simulation specific variables
172  //===================================================================
173 
175  double timestamp;
176 
179 
182 
184  Eigen::Vector3d true_bias_accel = Eigen::Vector3d::Zero();
185 
187  Eigen::Vector3d true_bias_gyro = Eigen::Vector3d::Zero();
188 
189  // Our history of true biases
190  std::vector<double> hist_true_bias_time;
191  std::vector<Eigen::Vector3d> hist_true_bias_accel;
192  std::vector<Eigen::Vector3d> hist_true_bias_gyro;
193 };
194 
195 } // namespace ov_init
196 
197 #endif // OV_INIT_SIMULATORINIT_H
std::vector< double > hist_true_bias_time
std::vector< Eigen::Vector3d > hist_true_bias_accel
std::mt19937 gen_state_init
Mersenne twister PRNG for state initialization.
std::vector< Eigen::VectorXd > traj_data
Our loaded trajectory data (timestamp(s), q_GtoI, p_IinG)
std::unordered_map< size_t, Eigen::Vector3d > featmap
bool ok()
Returns if we are actively simulating.
Definition: SimulatorInit.h:71
double timestamp
Current timestamp of the system.
State initialization code.
std::unordered_map< size_t, Eigen::Vector3d > get_map()
Returns the true 3d map of features.
std::mt19937 gen_meas_imu
Mersenne twister PRNG for measurements (IMU)
InertialInitializerOptions params
True params (a copy of the parsed ones)
std::shared_ptr< ov_core::BsplineSE3 > spline
Our b-spline trajectory.
double timestamp_last_imu
Last time we had an IMU reading.
InertialInitializerOptions get_true_parameters()
Access function to get the true parameters (i.e. calibration and settings)
std::vector< Eigen::Vector3d > hist_true_bias_gyro
double current_timestamp()
Gets the timestamp we have simulated up too.
Definition: SimulatorInit.h:77
Master simulator class that generated visual-inertial measurements.
Definition: SimulatorInit.h:52
std::mt19937 gen_state_perturb
Mersenne twister PRNG for state perturbations.
std::vector< std::mt19937 > gen_meas_cams
Mersenne twister PRNG for measurements (CAMERAS)
bool is_running
If our simulation is running.
double timestamp_last_cam
Last time we had an CAMERA reading.
Struct which stores all options needed for state estimation.


ov_init
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Wed Jun 21 2023 03:05:41