Master simulator class that generated visual-inertial measurements. More...
#include <SimulatorInit.h>
Public Member Functions | |
double | current_timestamp () |
Gets the timestamp we have simulated up too. More... | |
std::unordered_map< size_t, Eigen::Vector3d > | get_map () |
Returns the true 3d map of features. More... | |
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. More... | |
bool | get_next_imu (double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am) |
Gets the next inertial reading if we have one. More... | |
bool | get_state (double desired_time, Eigen::Matrix< double, 17, 1 > &imustate) |
Get the simulation state at a specified timestep. More... | |
InertialInitializerOptions | get_true_parameters () |
Access function to get the true parameters (i.e. calibration and settings) More... | |
bool | ok () |
Returns if we are actively simulating. More... | |
void | perturb_parameters (InertialInitializerOptions ¶ms_) |
Will get a set of perturbed parameters. More... | |
SimulatorInit (InertialInitializerOptions ¶ms_) | |
Default constructor, will load all configuration variables. More... | |
Protected Member Functions | |
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. More... | |
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. More... | |
Protected Attributes | |
std::unordered_map< size_t, Eigen::Vector3d > | featmap |
std::vector< std::mt19937 > | gen_meas_cams |
Mersenne twister PRNG for measurements (CAMERAS) More... | |
std::mt19937 | gen_meas_imu |
Mersenne twister PRNG for measurements (IMU) More... | |
std::mt19937 | gen_state_init |
Mersenne twister PRNG for state initialization. More... | |
std::mt19937 | gen_state_perturb |
Mersenne twister PRNG for state perturbations. More... | |
std::vector< Eigen::Vector3d > | hist_true_bias_accel |
std::vector< Eigen::Vector3d > | hist_true_bias_gyro |
std::vector< double > | hist_true_bias_time |
size_t | id_map = 0 |
Our map of 3d features. More... | |
bool | is_running |
If our simulation is running. More... | |
InertialInitializerOptions | params |
True params (a copy of the parsed ones) More... | |
std::shared_ptr< ov_core::BsplineSE3 > | spline |
Our b-spline trajectory. More... | |
double | timestamp |
Current timestamp of the system. More... | |
double | timestamp_last_cam |
Last time we had an CAMERA reading. More... | |
double | timestamp_last_imu |
Last time we had an IMU reading. More... | |
std::vector< Eigen::VectorXd > | traj_data |
Our loaded trajectory data (timestamp(s), q_GtoI, p_IinG) More... | |
Eigen::Vector3d | true_bias_accel = Eigen::Vector3d::Zero() |
Our running acceleration bias. More... | |
Eigen::Vector3d | true_bias_gyro = Eigen::Vector3d::Zero() |
Our running gyroscope bias. More... | |
Master simulator class that generated visual-inertial measurements.
Given a trajectory this will generate a SE(3) ov_core::BsplineSE3 for that trajectory. This allows us to get the inertial measurement information at each timestep during this trajectory. After creating the bspline we will generate an environmental feature map which will be used as our feature measurements. This map will be projected into the frame at each timestep to get our "raw" uv measurements. We inject bias and white noises into our inertial readings while adding our white noise to the uv measurements also. The user should specify the sensor rates that they desire along with the seeds of the random number generators.
Definition at line 52 of file SimulatorInit.h.
SimulatorInit::SimulatorInit | ( | InertialInitializerOptions & | params_ | ) |
Default constructor, will load all configuration variables.
params_ | InertialInitializer parameters. Should have already been loaded from cmd. |
Definition at line 34 of file SimulatorInit.cpp.
|
inline |
Gets the timestamp we have simulated up too.
Definition at line 77 of file SimulatorInit.h.
|
protected |
Will generate points in the fov of the specified camera.
R_GtoI | Orientation of the IMU pose | |
p_IinG | Position of the IMU pose | |
camid | Camera id of the camera sensor we want to project into | |
[out] | feats | Map we will append new features to |
numpts | Number of points we should generate |
Definition at line 461 of file SimulatorInit.cpp.
|
inline |
Returns the true 3d map of features.
Definition at line 106 of file SimulatorInit.h.
bool SimulatorInit::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.
time_cam | Time that this measurement occured at |
camids | Camera ids that the corresponding vectors match |
feats | Noisy uv measurements and ids for the returned time |
Definition at line 350 of file SimulatorInit.cpp.
bool SimulatorInit::get_next_imu | ( | double & | time_imu, |
Eigen::Vector3d & | wm, | ||
Eigen::Vector3d & | am | ||
) |
Gets the next inertial reading if we have one.
time_imu | Time that this measurement occured at |
wm | Angular velocity measurement in the inertial frame |
am | Linear velocity in the inertial frame |
Definition at line 289 of file SimulatorInit.cpp.
bool SimulatorInit::get_state | ( | double | desired_time, |
Eigen::Matrix< double, 17, 1 > & | imustate | ||
) |
Get the simulation state at a specified timestep.
desired_time | Timestamp we want to get the state at |
imustate | State in the MSCKF ordering: [time(sec),q_GtoI,p_IinG,v_IinG,b_gyro,b_accel] |
Definition at line 245 of file SimulatorInit.cpp.
|
inline |
Access function to get the true parameters (i.e. calibration and settings)
Definition at line 109 of file SimulatorInit.h.
|
inline |
Returns if we are actively simulating.
Definition at line 71 of file SimulatorInit.h.
void SimulatorInit::perturb_parameters | ( | InertialInitializerOptions & | params_ | ) |
Will get a set of perturbed parameters.
params_ | Parameters we will perturb |
Definition at line 203 of file SimulatorInit.cpp.
|
protected |
Projects the passed map features into the desired camera frame.
R_GtoI | Orientation of the IMU pose |
p_IinG | Position of the IMU pose |
camid | Camera id of the camera sensor we want to project into |
feats | Our set of 3d features |
Definition at line 413 of file SimulatorInit.cpp.
|
protected |
Definition at line 153 of file SimulatorInit.h.
|
protected |
Mersenne twister PRNG for measurements (CAMERAS)
Definition at line 159 of file SimulatorInit.h.
|
protected |
Mersenne twister PRNG for measurements (IMU)
Definition at line 156 of file SimulatorInit.h.
|
protected |
Mersenne twister PRNG for state initialization.
Definition at line 162 of file SimulatorInit.h.
|
protected |
Mersenne twister PRNG for state perturbations.
Definition at line 165 of file SimulatorInit.h.
|
protected |
Definition at line 191 of file SimulatorInit.h.
|
protected |
Definition at line 192 of file SimulatorInit.h.
|
protected |
Definition at line 190 of file SimulatorInit.h.
|
protected |
Our map of 3d features.
Definition at line 152 of file SimulatorInit.h.
|
protected |
If our simulation is running.
Definition at line 168 of file SimulatorInit.h.
|
protected |
True params (a copy of the parsed ones)
Definition at line 139 of file SimulatorInit.h.
|
protected |
Our b-spline trajectory.
Definition at line 149 of file SimulatorInit.h.
|
protected |
Current timestamp of the system.
Definition at line 175 of file SimulatorInit.h.
|
protected |
Last time we had an CAMERA reading.
Definition at line 181 of file SimulatorInit.h.
|
protected |
Last time we had an IMU reading.
Definition at line 178 of file SimulatorInit.h.
|
protected |
Our loaded trajectory data (timestamp(s), q_GtoI, p_IinG)
Definition at line 146 of file SimulatorInit.h.
|
protected |
Our running acceleration bias.
Definition at line 184 of file SimulatorInit.h.
|
protected |
Our running gyroscope bias.
Definition at line 187 of file SimulatorInit.h.