Go to the documentation of this file.
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>
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);
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;
207 #endif // OV_MSCKF_SIMULATOR_H
std::unordered_map< size_t, Eigen::Vector3d > featmap
bool get_state(double desired_time, Eigen::Matrix< double, 17, 1 > &imustate)
Get the simulation state at a specified timestep.
bool is_running
If our simulation is running.
double timestamp
Current timestamp of the system.
Extended Kalman Filter estimator.
VioManagerOptions params
True vio manager params (a copy of the parsed ones)
double timestamp_last_cam
Last time we had an CAMERA reading.
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::vector< Eigen::Vector3d > hist_true_bias_gyro
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 > get_map_vec()
Returns the true 3d map of features.
double current_timestamp()
Gets the timestamp we have simulated up too.
std::vector< double > hist_true_bias_time
std::vector< Eigen::Vector3d > hist_true_bias_accel
Eigen::Vector3d true_bias_gyro
Our running gyroscope bias.
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.
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.
Eigen::Vector3d true_bias_accel
Our running acceleration bias.
std::vector< std::mt19937 > gen_meas_cams
Mersenne twister PRNG for measurements (CAMERAS)
bool has_skipped_first_bias
std::mt19937 gen_state_init
Mersenne twister PRNG for state initialization.
size_t id_map
Our map of 3d features.
static void perturb_parameters(std::mt19937 gen_state, VioManagerOptions ¶ms_)
Will get a set of perturbed parameters.
Simulator(VioManagerOptions ¶ms_)
Default constructor, will load all configuration variables.
std::vector< Eigen::VectorXd > traj_data
Our loaded trajectory data (timestamp(s), q_GtoI, p_IinG)
Struct which stores all options needed for state estimation.
std::mt19937 gen_state_perturb
Mersenne twister PRNG for state perturbations.
VioManagerOptions get_true_parameters()
Access function to get the true parameters (i.e. calibration and settings)
double timestamp_last_imu
Last time we had an IMU reading.
bool get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am)
Gets the next inertial reading if we have one.
Master simulator class that generated visual-inertial measurements.
bool ok()
Returns if we are actively simulating.
std::mt19937 gen_meas_imu
Mersenne twister PRNG for measurements (IMU)
ov_msckf
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54