Go to the documentation of this file.
22 #ifndef OV_INIT_SIMULATORINIT_H
23 #define OV_INIT_SIMULATORINIT_H
25 #include <Eigen/Eigen>
27 #include <opencv2/core/core.hpp>
31 #include <unordered_map>
85 bool get_state(
double desired_time, Eigen::Matrix<double, 17, 1> &imustate);
94 bool get_next_imu(
double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am);
103 bool get_next_cam(
double &time_cam, std::vector<int> &camids, std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats);
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);
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);
149 std::shared_ptr<ov_core::BsplineSE3>
spline;
153 std::unordered_map<size_t, Eigen::Vector3d>
featmap;
197 #endif // OV_INIT_SIMULATORINIT_H
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.
double timestamp
Current timestamp of the system.
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.
std::unordered_map< size_t, Eigen::Vector3d > featmap
Struct which stores all options needed for state estimation.
std::vector< double > hist_true_bias_time
Eigen::Vector3d true_bias_gyro
Our running gyroscope bias.
double timestamp_last_cam
Last time we had an CAMERA reading.
InertialInitializerOptions params
True params (a copy of the parsed ones)
std::unordered_map< size_t, Eigen::Vector3d > get_map()
Returns the true 3d map of features.
std::shared_ptr< ov_core::BsplineSE3 > spline
Our b-spline trajectory.
std::vector< Eigen::Vector3d > hist_true_bias_gyro
std::vector< Eigen::VectorXd > traj_data
Our loaded trajectory data (timestamp(s), q_GtoI, p_IinG)
size_t id_map
Our map of 3d features.
bool get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am)
Gets the next inertial reading if we have one.
bool ok()
Returns if we are actively simulating.
std::mt19937 gen_state_perturb
Mersenne twister PRNG for state perturbations.
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.
std::mt19937 gen_meas_imu
Mersenne twister PRNG for measurements (IMU)
State initialization code.
Eigen::Vector3d true_bias_accel
Our running acceleration bias.
double current_timestamp()
Gets the timestamp we have simulated up too.
SimulatorInit(InertialInitializerOptions ¶ms_)
Default constructor, will load all configuration variables.
InertialInitializerOptions get_true_parameters()
Access function to get the true parameters (i.e. calibration and settings)
std::vector< std::mt19937 > gen_meas_cams
Mersenne twister PRNG for measurements (CAMERAS)
double timestamp_last_imu
Last time we had an IMU reading.
std::vector< Eigen::Vector3d > hist_true_bias_accel
void perturb_parameters(InertialInitializerOptions ¶ms_)
Will get a set of perturbed parameters.
Master simulator class that generated visual-inertial measurements.
std::mt19937 gen_state_init
Mersenne twister PRNG for state initialization.
bool is_running
If our simulation is running.
bool get_state(double desired_time, Eigen::Matrix< double, 17, 1 > &imustate)
Get the simulation state at a specified timestep.
ov_init
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:51