41 PRINT_DEBUG(
"=======================================\n");
42 PRINT_DEBUG(
"VISUAL-INERTIAL SIMULATOR STARTING\n");
43 PRINT_DEBUG(
"=======================================\n");
48 this->params = params_;
51 auto tmp_cast = std::dynamic_pointer_cast<ov_core::CamEqui>(tmp.second);
52 if (tmp_cast !=
nullptr) {
53 params.camera_intrinsics.insert({tmp.first, std::make_shared<ov_core::CamEqui>(tmp.second->w(), tmp.second->h())});
54 params.camera_intrinsics.at(tmp.first)->set_value(params_.
camera_intrinsics.at(tmp.first)->get_value());
56 params.camera_intrinsics.insert({tmp.first, std::make_shared<ov_core::CamRadtan>(tmp.second->w(), tmp.second->h())});
57 params.camera_intrinsics.at(tmp.first)->set_value(params_.
camera_intrinsics.at(tmp.first)->get_value());
63 spline = std::make_shared<ov_core::BsplineSE3>();
64 spline->feed_trajectory(traj_data);
67 timestamp = spline->get_start_time();
68 timestamp_last_imu = spline->get_start_time();
69 timestamp_last_cam = spline->get_start_time();
72 Eigen::Matrix3d R_GtoI_init;
73 Eigen::Vector3d p_IinG_init;
74 bool success_pose_init = spline->get_pose(timestamp, R_GtoI_init, p_IinG_init);
75 if (!success_pose_init) {
77 std::exit(EXIT_FAILURE);
81 double distance = 0.0;
82 double distancethreshold = params.sim_distance_threshold;
86 Eigen::Matrix3d R_GtoI;
87 Eigen::Vector3d p_IinG;
88 bool success_pose = spline->get_pose(timestamp, R_GtoI, p_IinG);
92 PRINT_ERROR(
RED "[SIM]: unable to find jolt in the groundtruth data to initialize at\n" RESET);
93 std::exit(EXIT_FAILURE);
97 distance += (p_IinG - p_IinG_init).norm();
101 if (distance > distancethreshold) {
104 timestamp += 1.0 / params.sim_freq_cam;
105 timestamp_last_imu += 1.0 / params.sim_freq_cam;
106 timestamp_last_cam += 1.0 / params.sim_freq_cam;
109 PRINT_DEBUG(
"[SIM]: moved %.3f seconds into the dataset where it starts moving\n", timestamp - spline->get_start_time());
112 hist_true_bias_time.push_back(timestamp_last_imu - 1.0 / params.sim_freq_imu);
113 hist_true_bias_accel.push_back(true_bias_accel);
114 hist_true_bias_gyro.push_back(true_bias_gyro);
115 hist_true_bias_time.push_back(timestamp_last_imu);
116 hist_true_bias_accel.push_back(true_bias_accel);
117 hist_true_bias_gyro.push_back(true_bias_gyro);
118 hist_true_bias_time.push_back(timestamp_last_imu + 1.0 / params.sim_freq_imu);
119 hist_true_bias_accel.push_back(true_bias_accel);
120 hist_true_bias_gyro.push_back(true_bias_gyro);
129 gen_state_init = std::mt19937(params.sim_seed_state_init);
130 gen_state_init.seed(params.sim_seed_state_init);
131 gen_state_perturb = std::mt19937(params.sim_seed_preturb);
132 gen_state_perturb.seed(params.sim_seed_preturb);
133 gen_meas_imu = std::mt19937(params.sim_seed_measurements);
134 gen_meas_imu.seed(params.sim_seed_measurements);
137 for (
int i = 0; i < params.state_options.num_cameras; i++) {
138 gen_meas_cams.push_back(std::mt19937(params.sim_seed_measurements));
139 gen_meas_cams.at(i).seed(params.sim_seed_measurements);
146 if (params.sim_do_perturbation) {
149 perturb_parameters(gen_state_perturb, params_);
152 params.print_and_load_estimator();
153 params.print_and_load_noise();
154 params.print_and_load_state();
155 params.print_and_load_trackers();
156 params.print_and_load_simulation();
165 size_t mapsize = featmap.size();
166 PRINT_DEBUG(
"[SIM]: Generating map features at %d rate\n", (
int)(1.0 / dt));
171 for (
int i = 0; i < params.state_options.num_cameras; i++) {
174 double time_synth = spline->get_start_time();
180 Eigen::Matrix3d R_GtoI;
181 Eigen::Vector3d p_IinG;
182 bool success_pose = spline->get_pose(time_synth, R_GtoI, p_IinG);
189 std::vector<std::pair<size_t, Eigen::VectorXf>> uvs = project_pointcloud(R_GtoI, p_IinG, i, featmap);
191 if ((
int)uvs.size() < params.num_pts) {
192 generate_points(R_GtoI, p_IinG, i, featmap, params.num_pts - (
int)uvs.size());
200 PRINT_DEBUG(
"[SIM]: Generated %d map features in total over %d frames (camera %d)\n", (
int)(featmap.size() - mapsize),
201 (
int)((time_synth - spline->get_start_time()) / dt), i);
202 mapsize = featmap.size();
212 std::normal_distribution<double> w(0, 1);
222 for (
int r = 0; r < 4; r++) {
223 intrinsics(r) += 1.0 * w(gen_state);
225 for (
int r = 4; r < 8; r++) {
226 intrinsics(r) += 0.005 * w(gen_state);
231 Eigen::Vector3d w_vec;
232 w_vec << 0.001 * w(gen_state), 0.001 * w(gen_state), 0.001 * w(gen_state);
237 for (
int r = 4; r < 7; r++) {
244 for (
int j = 0; j < 6; j++) {
245 params_.
vec_dw(j) += 0.004 * w(gen_state);
246 params_.
vec_da(j) += 0.004 * w(gen_state);
249 Eigen::Vector3d w_vec;
250 w_vec << 0.002 * w(gen_state), 0.002 * w(gen_state), 0.002 * w(gen_state);
253 Eigen::Vector3d w_vec;
254 w_vec << 0.002 * w(gen_state), 0.002 * w(gen_state), 0.002 * w(gen_state);
261 for (
int j = 0; j < 9; j++) {
262 params_.
vec_tg(j) += 0.004 * w(gen_state);
267 bool Simulator::get_state(
double desired_time, Eigen::Matrix<double, 17, 1> &imustate) {
274 Eigen::Matrix3d R_GtoI;
275 Eigen::Vector3d p_IinG, w_IinI, v_IinG;
278 bool success_vel = spline->get_velocity(desired_time, R_GtoI, p_IinG, w_IinI, v_IinG);
281 bool success_bias =
false;
283 for (
size_t i = 0; i < hist_true_bias_time.size() - 1; i++) {
284 if (hist_true_bias_time.at(i) < desired_time && hist_true_bias_time.at(i + 1) >= desired_time) {
292 if (!success_vel || !success_bias) {
297 double lambda = (desired_time - hist_true_bias_time.at(id_loc)) / (hist_true_bias_time.at(id_loc + 1) - hist_true_bias_time.at(id_loc));
298 Eigen::Vector3d true_bg_interp = (1 - lambda) * hist_true_bias_gyro.at(id_loc) + lambda * hist_true_bias_gyro.at(id_loc + 1);
299 Eigen::Vector3d true_ba_interp = (1 - lambda) * hist_true_bias_accel.at(id_loc) + lambda * hist_true_bias_accel.at(id_loc + 1);
302 imustate(0, 0) = desired_time;
303 imustate.block(1, 0, 4, 1) =
rot_2_quat(R_GtoI);
304 imustate.block(5, 0, 3, 1) = p_IinG;
305 imustate.block(8, 0, 3, 1) = v_IinG;
306 imustate.block(11, 0, 3, 1) = true_bg_interp;
307 imustate.block(14, 0, 3, 1) = true_ba_interp;
311 bool Simulator::get_next_imu(
double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am) {
314 if (timestamp_last_cam + 1.0 / params.sim_freq_cam < timestamp_last_imu + 1.0 / params.sim_freq_imu)
318 timestamp_last_imu += 1.0 / params.sim_freq_imu;
319 timestamp = timestamp_last_imu;
320 time_imu = timestamp_last_imu;
323 Eigen::Matrix3d R_GtoI;
324 Eigen::Vector3d p_IinG, w_IinI, v_IinG, alpha_IinI, a_IinG;
330 bool success_accel = spline->get_acceleration(timestamp, R_GtoI, p_IinG, w_IinI, v_IinG, alpha_IinI, a_IinG);
334 if (!success_accel) {
340 Eigen::Vector3d gravity;
341 gravity << 0.0, 0.0, params.gravity_mag;
342 Eigen::Vector3d accel_inI = R_GtoI * (a_IinG + gravity);
343 Eigen::Vector3d omega_inI = w_IinI;
348 Eigen::Matrix3d Dw = State::Dm(params.state_options.imu_model, params.vec_dw);
349 Eigen::Matrix3d Da = State::Dm(params.state_options.imu_model, params.vec_da);
350 Eigen::Matrix3d Tg = State::Tg(params.vec_tg);
353 Eigen::Matrix3d Tw = Dw.colPivHouseholderQr().solve(Eigen::Matrix3d::Identity());
354 Eigen::Matrix3d Ta = Da.colPivHouseholderQr().solve(Eigen::Matrix3d::Identity());
355 Eigen::Vector3d omega_inGYRO = Tw *
quat_2_Rot(params.q_GYROtoIMU).transpose() * omega_inI + Tg * accel_inI;
356 Eigen::Vector3d accel_inACC = Ta *
quat_2_Rot(params.q_ACCtoIMU).transpose() * accel_inI;
360 double dt = 1.0 / params.sim_freq_imu;
361 std::normal_distribution<double> w(0, 1);
362 if (has_skipped_first_bias) {
365 true_bias_gyro(0) += params.imu_noises.sigma_wb * std::sqrt(dt) * w(gen_meas_imu);
366 true_bias_gyro(1) += params.imu_noises.sigma_wb * std::sqrt(dt) * w(gen_meas_imu);
367 true_bias_gyro(2) += params.imu_noises.sigma_wb * std::sqrt(dt) * w(gen_meas_imu);
368 true_bias_accel(0) += params.imu_noises.sigma_ab * std::sqrt(dt) * w(gen_meas_imu);
369 true_bias_accel(1) += params.imu_noises.sigma_ab * std::sqrt(dt) * w(gen_meas_imu);
370 true_bias_accel(2) += params.imu_noises.sigma_ab * std::sqrt(dt) * w(gen_meas_imu);
373 hist_true_bias_time.push_back(timestamp_last_imu);
374 hist_true_bias_gyro.push_back(true_bias_gyro);
375 hist_true_bias_accel.push_back(true_bias_accel);
377 has_skipped_first_bias =
true;
380 wm(0) = omega_inGYRO(0) + true_bias_gyro(0) + params.imu_noises.sigma_w / std::sqrt(dt) * w(gen_meas_imu);
381 wm(1) = omega_inGYRO(1) + true_bias_gyro(1) + params.imu_noises.sigma_w / std::sqrt(dt) * w(gen_meas_imu);
382 wm(2) = omega_inGYRO(2) + true_bias_gyro(2) + params.imu_noises.sigma_w / std::sqrt(dt) * w(gen_meas_imu);
383 am(0) = accel_inACC(0) + true_bias_accel(0) + params.imu_noises.sigma_a / std::sqrt(dt) * w(gen_meas_imu);
384 am(1) = accel_inACC(1) + true_bias_accel(1) + params.imu_noises.sigma_a / std::sqrt(dt) * w(gen_meas_imu);
385 am(2) = accel_inACC(2) + true_bias_accel(2) + params.imu_noises.sigma_a / std::sqrt(dt) * w(gen_meas_imu);
391 bool Simulator::get_next_cam(
double &time_cam, std::vector<int> &camids,
392 std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats) {
395 if (timestamp_last_imu + 1.0 / params.sim_freq_imu < timestamp_last_cam + 1.0 / params.sim_freq_cam)
399 timestamp_last_cam += 1.0 / params.sim_freq_cam;
400 timestamp = timestamp_last_cam;
401 time_cam = timestamp_last_cam - params.calib_camimu_dt;
404 Eigen::Matrix3d R_GtoI;
405 Eigen::Vector3d p_IinG;
406 bool success_pose = spline->get_pose(timestamp, R_GtoI, p_IinG);
415 for (
int i = 0; i < params.state_options.num_cameras; i++) {
418 std::vector<std::pair<size_t, Eigen::VectorXf>> uvs = project_pointcloud(R_GtoI, p_IinG, i, featmap);
421 if ((
int)uvs.size() < params.num_pts) {
422 PRINT_WARNING(
YELLOW "[SIM]: cam %d was unable to generate enough features (%d < %d projections)\n" RESET, (
int)i, (
int)uvs.size(),
427 if ((
int)uvs.size() > params.num_pts) {
428 uvs.erase(uvs.begin() + params.num_pts, uvs.end());
433 for (
size_t f = 0;
f < uvs.size() && !params.use_stereo;
f++) {
434 uvs.at(
f).first += i * featmap.size();
438 std::normal_distribution<double> w(0, 1);
439 for (
size_t j = 0; j < uvs.size(); j++) {
440 uvs.at(j).second(0) += params.msckf_options.sigma_pix * w(gen_meas_cams.at(i));
441 uvs.at(j).second(1) += params.msckf_options.sigma_pix * w(gen_meas_cams.at(i));
445 feats.push_back(uvs);
453 std::vector<std::pair<size_t, Eigen::VectorXf>> Simulator::project_pointcloud(
const Eigen::Matrix3d &R_GtoI,
const Eigen::Vector3d &p_IinG,
455 const std::unordered_map<size_t, Eigen::Vector3d> &feats) {
458 assert(camid < params.state_options.num_cameras);
459 assert((
int)params.camera_intrinsics.size() == params.state_options.num_cameras);
460 assert((
int)params.camera_extrinsics.size() == params.state_options.num_cameras);
463 Eigen::Matrix<double, 3, 3> R_ItoC =
quat_2_Rot(params.camera_extrinsics.at(camid).block(0, 0, 4, 1));
464 Eigen::Matrix<double, 3, 1> p_IinC = params.camera_extrinsics.at(camid).block(4, 0, 3, 1);
465 std::shared_ptr<ov_core::CamBase> camera = params.camera_intrinsics.at(camid);
468 std::vector<std::pair<size_t, Eigen::VectorXf>> uvs;
471 for (
const auto &feat : feats) {
474 Eigen::Vector3d p_FinI = R_GtoI * (feat.second - p_IinG);
475 Eigen::Vector3d p_FinC = R_ItoC * p_FinI + p_IinC;
478 if (p_FinC(2) > params.sim_max_feature_gen_distance || p_FinC(2) < 0.1)
482 Eigen::Vector2f uv_norm;
483 uv_norm << (float)(p_FinC(0) / p_FinC(2)), (
float)(p_FinC(1) / p_FinC(2));
486 Eigen::Vector2f uv_dist = camera->distort_f(uv_norm);
489 if (uv_dist(0) < 0 || uv_dist(0) > camera->w() || uv_dist(1) < 0 || uv_dist(1) > camera->h()) {
494 uvs.push_back({feat.first, uv_dist});
501 void Simulator::generate_points(
const Eigen::Matrix3d &R_GtoI,
const Eigen::Vector3d &p_IinG,
int camid,
502 std::unordered_map<size_t, Eigen::Vector3d> &feats,
int numpts) {
505 assert(camid < params.state_options.num_cameras);
506 assert((
int)params.camera_intrinsics.size() == params.state_options.num_cameras);
507 assert((
int)params.camera_extrinsics.size() == params.state_options.num_cameras);
510 Eigen::Matrix<double, 3, 3> R_ItoC =
quat_2_Rot(params.camera_extrinsics.at(camid).block(0, 0, 4, 1));
511 Eigen::Matrix<double, 3, 1> p_IinC = params.camera_extrinsics.at(camid).block(4, 0, 3, 1);
512 std::shared_ptr<ov_core::CamBase> camera = params.camera_intrinsics.at(camid);
515 for (
int i = 0; i < numpts; i++) {
518 std::uniform_real_distribution<double> gen_u(0, camera->w());
519 std::uniform_real_distribution<double> gen_v(0, camera->h());
520 double u_dist = gen_u(gen_state_init);
521 double v_dist = gen_v(gen_state_init);
524 cv::Point2f uv_dist((
float)u_dist, (
float)v_dist);
527 cv::Point2f uv_norm = camera->undistort_cv(uv_dist);
530 std::uniform_real_distribution<double> gen_depth(params.sim_min_feature_gen_distance, params.sim_max_feature_gen_distance);
531 double depth = gen_depth(gen_state_init);
534 Eigen::Vector3d bearing;
535 bearing << uv_norm.x, uv_norm.y, 1;
536 Eigen::Vector3d p_FinC;
537 p_FinC = depth * bearing;
540 Eigen::Vector3d p_FinI = R_ItoC.transpose() * (p_FinC - p_IinC);
541 Eigen::Vector3d p_FinG = R_GtoI.transpose() * p_FinI + p_IinG;
544 featmap.insert({id_map, p_FinG});