22 #ifndef OV_MSCKF_SIMULATOR_H 23 #define OV_MSCKF_SIMULATOR_H 25 #include <Eigen/Eigen> 27 #include <opencv2/core/core.hpp> 31 #include <unordered_map> 66 static void perturb_parameters(std::mt19937 gen_state,
VioManagerOptions ¶ms_);
72 bool ok() {
return is_running; }
86 bool get_state(
double desired_time, Eigen::Matrix<double, 17, 1> &imustate);
95 bool get_next_imu(
double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am);
104 bool get_next_cam(
double &time_cam, std::vector<int> &camids, std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats);
107 std::unordered_map<size_t, Eigen::Vector3d>
get_map() {
return featmap; }
111 std::vector<Eigen::Vector3d> feats;
112 for (
auto const &feat : featmap)
113 feats.push_back(feat.second);
129 std::vector<std::pair<size_t, Eigen::VectorXf>> project_pointcloud(
const Eigen::Matrix3d &R_GtoI,
const Eigen::Vector3d &p_IinG,
130 int camid,
const std::unordered_map<size_t, Eigen::Vector3d> &feats);
140 void generate_points(
const Eigen::Matrix3d &R_GtoI,
const Eigen::Vector3d &p_IinG,
int camid,
141 std::unordered_map<size_t, Eigen::Vector3d> &feats,
int numpts);
158 std::shared_ptr<ov_core::BsplineSE3>
spline;
162 std::unordered_map<size_t, Eigen::Vector3d>
featmap;
193 Eigen::Vector3d true_bias_accel = Eigen::Vector3d::Zero();
196 Eigen::Vector3d true_bias_gyro = Eigen::Vector3d::Zero();
199 bool has_skipped_first_bias =
false;
207 #endif // OV_MSCKF_SIMULATOR_H std::vector< std::mt19937 > gen_meas_cams
Mersenne twister PRNG for measurements (CAMERAS)
Extended Kalman Filter estimator.
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)
VioManagerOptions get_true_parameters()
Access function to get the true parameters (i.e. calibration and settings)
std::mt19937 gen_state_perturb
Mersenne twister PRNG for state perturbations.
bool ok()
Returns if we are actively simulating.
double timestamp_last_imu
Last time we had an IMU reading.
double timestamp
Current timestamp of the system.
bool is_running
If our simulation is running.
std::unordered_map< size_t, Eigen::Vector3d > featmap
Struct which stores all options needed for state estimation.
std::mt19937 gen_meas_imu
Mersenne twister PRNG for measurements (IMU)
double timestamp_last_cam
Last time we had an CAMERA reading.
std::vector< Eigen::Vector3d > hist_true_bias_gyro
VioManagerOptions params
True vio manager params (a copy of the parsed ones)
std::shared_ptr< ov_core::BsplineSE3 > spline
Our b-spline trajectory.
std::vector< Eigen::Vector3d > get_map_vec()
Returns the true 3d map of features.
Master simulator class that generated visual-inertial measurements.
std::unordered_map< size_t, Eigen::Vector3d > get_map()
Returns the true 3d map of features.
std::vector< double > hist_true_bias_time
double current_timestamp()
Gets the timestamp we have simulated up too.
std::vector< Eigen::Vector3d > hist_true_bias_accel