class
SimulatorInitMaster simulator class that generated visual-inertial measurements.
Contents
Given a trajectory this will generate a SE(3) ov_core::
Constructors, destructors, conversion operators
- SimulatorInit(InertialInitializerOptions& params_)
- Default constructor, will load all configuration variables.
Public functions
- void perturb_parameters(InertialInitializerOptions& params_)
- Will get a set of perturbed parameters.
- auto ok() -> bool
- Returns if we are actively simulating.
- auto current_timestamp() -> double
- Gets the timestamp we have simulated up too.
- auto get_state(double desired_time, Eigen::Matrix<double, 17, 1>& imustate) -> bool
- Get the simulation state at a specified timestep.
- auto get_next_imu(double& time_imu, Eigen::Vector3d& wm, Eigen::Vector3d& am) -> bool
- Gets the next inertial reading if we have one.
- auto get_next_cam(double& time_cam, std::vector<int>& camids, std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>>& feats) -> bool
- Gets the next inertial reading if we have one.
- auto get_map() -> std::unordered_map<size_t, Eigen::Vector3d>
- Returns the true 3d map of features.
- auto get_true_parameters() -> InertialInitializerOptions
- Access function to get the true parameters (i.e. calibration and settings)
Protected functions
- auto project_pointcloud(const Eigen::Matrix3d& R_GtoI, const Eigen::Vector3d& p_IinG, int camid, const std::unordered_map<size_t, Eigen::Vector3d>& feats) -> std::vector<std::pair<size_t, Eigen::VectorXf>>
- Projects the passed map features into the desired camera frame.
- 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.
Protected variables
- InertialInitializerOptions params
- True params (a copy of the parsed ones)
- std::vector<Eigen::VectorXd> traj_data
- Our loaded trajectory data (timestamp(s), q_GtoI, p_IinG)
-
std::shared_ptr<ov_core::
BsplineSE3> spline - Our b-spline trajectory.
- size_t id_map
- Our map of 3d features.
- std::mt19937 gen_meas_imu
- Mersenne twister PRNG for measurements (IMU)
- std::vector<std::mt19937> gen_meas_cams
- Mersenne twister PRNG for measurements (CAMERAS)
- std::mt19937 gen_state_init
- Mersenne twister PRNG for state initialization.
- std::mt19937 gen_state_perturb
- Mersenne twister PRNG for state perturbations.
- bool is_running
- If our simulation is running.
- double timestamp
- Current timestamp of the system.
- double timestamp_last_imu
- Last time we had an IMU reading.
- double timestamp_last_cam
- Last time we had an CAMERA reading.
- Eigen::Vector3d true_bias_accel
- Our running acceleration bias.
- Eigen::Vector3d true_bias_gyro
- Our running gyroscope bias.
Function documentation
ov_init:: SimulatorInit:: SimulatorInit(InertialInitializerOptions& params_)
Default constructor, will load all configuration variables.
Parameters | |
---|---|
params_ | InertialInitializer parameters. Should have already been loaded from cmd. |
void ov_init:: SimulatorInit:: perturb_parameters(InertialInitializerOptions& params_)
Will get a set of perturbed parameters.
Parameters | |
---|---|
params_ | Parameters we will perturb |
bool ov_init:: SimulatorInit:: ok()
Returns if we are actively simulating.
Returns | True if we still have simulation data |
---|
double ov_init:: SimulatorInit:: current_timestamp()
Gets the timestamp we have simulated up too.
Returns | Timestamp |
---|
bool ov_init:: SimulatorInit:: get_state(double desired_time,
Eigen::Matrix<double, 17, 1>& imustate)
Get the simulation state at a specified timestep.
Parameters | |
---|---|
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] |
Returns | True if we have a state |
bool ov_init:: SimulatorInit:: get_next_imu(double& time_imu,
Eigen::Vector3d& wm,
Eigen::Vector3d& am)
Gets the next inertial reading if we have one.
Parameters | |
---|---|
time_imu | Time that this measurement occured at |
wm | Angular velocity measurement in the inertial frame |
am | Linear velocity in the inertial frame |
Returns | True if we have a measurement |
bool ov_init:: 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.
Parameters | |
---|---|
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 |
Returns | True if we have a measurement |
std::vector<std::pair<size_t, Eigen::VectorXf>> ov_init:: SimulatorInit:: project_pointcloud(const Eigen::Matrix3d& R_GtoI,
const Eigen::Vector3d& p_IinG,
int camid,
const std::unordered_map<size_t, Eigen::Vector3d>& feats) protected
Projects the passed map features into the desired camera frame.
Parameters | |
---|---|
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 |
Returns | True distorted raw image measurements and their ids for the specified camera |
void ov_init:: SimulatorInit:: generate_points(const Eigen::Matrix3d& R_GtoI,
const Eigen::Vector3d& p_IinG,
int camid,
std::unordered_map<size_t, Eigen::Vector3d>& feats,
int numpts) protected
Will generate points in the fov of the specified camera.
Parameters | |
---|---|
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 out | Map we will append new features to |
numpts | Number of points we should generate |