Master simulator class that generated visual-inertial measurements. More...
#include <Simulator.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... | |
std::vector< Eigen::Vector3d > | get_map_vec () |
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... | |
VioManagerOptions | 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... | |
Simulator (VioManagerOptions ¶ms_) | |
Default constructor, will load all configuration variables. More... | |
Static Public Member Functions | |
static void | perturb_parameters (std::mt19937 gen_state, VioManagerOptions ¶ms_) |
Will get a set of perturbed parameters. 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... | |
bool | has_skipped_first_bias = false |
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... | |
VioManagerOptions | params |
True vio manager 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 Simulator.h.
Simulator::Simulator | ( | VioManagerOptions & | params_ | ) |
Default constructor, will load all configuration variables.
params_ | VioManager parameters. Should have already been loaded from cmd. |
Definition at line 35 of file Simulator.cpp.
|
inline |
Gets the timestamp we have simulated up too.
Definition at line 78 of file Simulator.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 501 of file Simulator.cpp.
|
inline |
Returns the true 3d map of features.
Definition at line 107 of file Simulator.h.
|
inline |
Returns the true 3d map of features.
Definition at line 110 of file Simulator.h.
bool Simulator::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 391 of file Simulator.cpp.
bool Simulator::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 311 of file Simulator.cpp.
bool Simulator::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 267 of file Simulator.cpp.
|
inline |
Access function to get the true parameters (i.e. calibration and settings)
Definition at line 118 of file Simulator.h.
|
inline |
Returns if we are actively simulating.
Definition at line 72 of file Simulator.h.
|
static |
Will get a set of perturbed parameters.
gen_state | Random number gen to use |
params_ | Parameters we will perturb |
Definition at line 209 of file Simulator.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 453 of file Simulator.cpp.
|
protected |
Definition at line 162 of file Simulator.h.
|
protected |
Mersenne twister PRNG for measurements (CAMERAS)
Definition at line 168 of file Simulator.h.
|
protected |
Mersenne twister PRNG for measurements (IMU)
Definition at line 165 of file Simulator.h.
|
protected |
Mersenne twister PRNG for state initialization.
Definition at line 171 of file Simulator.h.
|
protected |
Mersenne twister PRNG for state perturbations.
Definition at line 174 of file Simulator.h.
|
protected |
Definition at line 199 of file Simulator.h.
|
protected |
Definition at line 201 of file Simulator.h.
|
protected |
Definition at line 202 of file Simulator.h.
|
protected |
Definition at line 200 of file Simulator.h.
|
protected |
Our map of 3d features.
Definition at line 161 of file Simulator.h.
|
protected |
If our simulation is running.
Definition at line 177 of file Simulator.h.
|
protected |
True vio manager params (a copy of the parsed ones)
Definition at line 148 of file Simulator.h.
|
protected |
Our b-spline trajectory.
Definition at line 158 of file Simulator.h.
|
protected |
Current timestamp of the system.
Definition at line 184 of file Simulator.h.
|
protected |
Last time we had an CAMERA reading.
Definition at line 190 of file Simulator.h.
|
protected |
Last time we had an IMU reading.
Definition at line 187 of file Simulator.h.
|
protected |
Our loaded trajectory data (timestamp(s), q_GtoI, p_IinG)
Definition at line 155 of file Simulator.h.
|
protected |
Our running acceleration bias.
Definition at line 193 of file Simulator.h.
|
protected |
Our running gyroscope bias.
Definition at line 196 of file Simulator.h.