Simulator.cpp
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #include "Simulator.h"
23 
24 #include "cam/CamBase.h"
25 #include "cam/CamEqui.h"
26 #include "cam/CamRadtan.h"
27 #include "sim/BsplineSE3.h"
28 #include "state/State.h"
29 #include "utils/colors.h"
30 #include "utils/dataset_reader.h"
31 
32 using namespace ov_core;
33 using namespace ov_msckf;
34 
35 Simulator::Simulator(VioManagerOptions &params_) {
36 
37  //===============================================================
38  //===============================================================
39 
40  // Nice startup message
41  PRINT_DEBUG("=======================================\n");
42  PRINT_DEBUG("VISUAL-INERTIAL SIMULATOR STARTING\n");
43  PRINT_DEBUG("=======================================\n");
44 
45  // Store a copy of our params
46  // NOTE: We need to explicitly create a copy of our shared pointers to the camera objects
47  // NOTE: Otherwise if we perturb it would also change our "true" parameters
48  this->params = params_;
49  params.camera_intrinsics.clear();
50  for (auto const &tmp : params_.camera_intrinsics) {
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());
55  } else {
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());
58  }
59  }
60 
61  // Load the groundtruth trajectory and its spline
62  DatasetReader::load_simulated_trajectory(params.sim_traj_path, traj_data);
63  spline = std::make_shared<ov_core::BsplineSE3>();
64  spline->feed_trajectory(traj_data);
65 
66  // Set all our timestamps as starting from the minimum spline time
67  timestamp = spline->get_start_time();
68  timestamp_last_imu = spline->get_start_time();
69  timestamp_last_cam = spline->get_start_time();
70 
71  // Get the pose at the current timestep
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) {
76  PRINT_ERROR(RED "[SIM]: unable to find the first pose in the spline...\n" RESET);
77  std::exit(EXIT_FAILURE);
78  }
79 
80  // Find the timestamp that we move enough to be considered "moved"
81  double distance = 0.0;
82  double distancethreshold = params.sim_distance_threshold;
83  while (true) {
84 
85  // Get the pose at the current timestep
86  Eigen::Matrix3d R_GtoI;
87  Eigen::Vector3d p_IinG;
88  bool success_pose = spline->get_pose(timestamp, R_GtoI, p_IinG);
89 
90  // Check if it fails
91  if (!success_pose) {
92  PRINT_ERROR(RED "[SIM]: unable to find jolt in the groundtruth data to initialize at\n" RESET);
93  std::exit(EXIT_FAILURE);
94  }
95 
96  // Append to our scalar distance
97  distance += (p_IinG - p_IinG_init).norm();
98  p_IinG_init = p_IinG;
99 
100  // Now check if we have an acceleration, else move forward in time
101  if (distance > distancethreshold) {
102  break;
103  } else {
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;
107  }
108  }
109  PRINT_DEBUG("[SIM]: moved %.3f seconds into the dataset where it starts moving\n", timestamp - spline->get_start_time());
110 
111  // Append the current true bias to our history
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);
121 
122  // Our simulation is running
123  is_running = true;
124 
125  //===============================================================
126  //===============================================================
127 
128  // Load the seeds for the random number generators
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);
135 
136  // Create generator for our camera
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);
140  }
141 
142  //===============================================================
143  //===============================================================
144 
145  // Perturb all calibration if we should
146  if (params.sim_do_perturbation) {
147 
148  // Do the perturbation
149  perturb_parameters(gen_state_perturb, params_);
150 
151  // Debug print simulation parameters
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();
157  }
158 
159  //===============================================================
160  //===============================================================
161 
162  // We will create synthetic camera frames and ensure that each has enough features
163  // double dt = 0.25/freq_cam;
164  double dt = 0.25;
165  size_t mapsize = featmap.size();
166  PRINT_DEBUG("[SIM]: Generating map features at %d rate\n", (int)(1.0 / dt));
167 
168  // Loop through each camera
169  // NOTE: we loop through cameras here so that the feature map for camera 1 will always be the same
170  // NOTE: thus when we add more cameras the first camera should get the same measurements
171  for (int i = 0; i < params.state_options.num_cameras; i++) {
172 
173  // Reset the start time
174  double time_synth = spline->get_start_time();
175 
176  // Loop through each pose and generate our feature map in them!!!!
177  while (true) {
178 
179  // Get the pose at the current timestep
180  Eigen::Matrix3d R_GtoI;
181  Eigen::Vector3d p_IinG;
182  bool success_pose = spline->get_pose(time_synth, R_GtoI, p_IinG);
183 
184  // We have finished generating features
185  if (!success_pose)
186  break;
187 
188  // Get the uv features for this frame
189  std::vector<std::pair<size_t, Eigen::VectorXf>> uvs = project_pointcloud(R_GtoI, p_IinG, i, featmap);
190  // If we do not have enough, generate more
191  if ((int)uvs.size() < params.num_pts) {
192  generate_points(R_GtoI, p_IinG, i, featmap, params.num_pts - (int)uvs.size());
193  }
194 
195  // Move forward in time
196  time_synth += dt;
197  }
198 
199  // Debug print
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();
203  }
204 
205  // Nice sleep so the user can look at the printout
206  sleep(1);
207 }
208 
209 void Simulator::perturb_parameters(std::mt19937 gen_state, VioManagerOptions &params_) {
210 
211  // One std generator
212  std::normal_distribution<double> w(0, 1);
213 
214  // Camera IMU offset
215  params_.calib_camimu_dt += 0.01 * w(gen_state);
216 
217  // Camera intrinsics and extrinsics
218  for (int i = 0; i < params_.state_options.num_cameras; i++) {
219 
220  // Camera intrinsic properties (k1, k2, p1, p2, r1, r2, r3, r4)
221  Eigen::MatrixXd intrinsics = params_.camera_intrinsics.at(i)->get_value();
222  for (int r = 0; r < 4; r++) {
223  intrinsics(r) += 1.0 * w(gen_state);
224  }
225  for (int r = 4; r < 8; r++) {
226  intrinsics(r) += 0.005 * w(gen_state);
227  }
228  params_.camera_intrinsics.at(i)->set_value(intrinsics);
229 
230  // Our camera extrinsics transform (orientation)
231  Eigen::Vector3d w_vec;
232  w_vec << 0.001 * w(gen_state), 0.001 * w(gen_state), 0.001 * w(gen_state);
233  params_.camera_extrinsics.at(i).block(0, 0, 4, 1) =
234  rot_2_quat(exp_so3(w_vec) * quat_2_Rot(params_.camera_extrinsics.at(i).block(0, 0, 4, 1)));
235 
236  // Our camera extrinsics transform (position)
237  for (int r = 4; r < 7; r++) {
238  params_.camera_extrinsics.at(i)(r) += 0.01 * w(gen_state);
239  }
240  }
241 
242  // If we need to perturb the imu intrinsics
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);
247  }
248  if (params_.state_options.imu_model == StateOptions::ImuModel::KALIBR) {
249  Eigen::Vector3d w_vec;
250  w_vec << 0.002 * w(gen_state), 0.002 * w(gen_state), 0.002 * w(gen_state);
251  params_.q_GYROtoIMU = rot_2_quat(exp_so3(w_vec) * quat_2_Rot(params_.q_GYROtoIMU));
252  } else {
253  Eigen::Vector3d w_vec;
254  w_vec << 0.002 * w(gen_state), 0.002 * w(gen_state), 0.002 * w(gen_state);
255  params_.q_ACCtoIMU = rot_2_quat(exp_so3(w_vec) * quat_2_Rot(params_.q_ACCtoIMU));
256  }
257  }
258 
259  // If we need to perturb gravity sensitivity
261  for (int j = 0; j < 9; j++) {
262  params_.vec_tg(j) += 0.004 * w(gen_state);
263  }
264  }
265 }
266 
267 bool Simulator::get_state(double desired_time, Eigen::Matrix<double, 17, 1> &imustate) {
268 
269  // Set to default state
270  imustate.setZero();
271  imustate(4) = 1;
272 
273  // Current state values
274  Eigen::Matrix3d R_GtoI;
275  Eigen::Vector3d p_IinG, w_IinI, v_IinG;
276 
277  // Get the pose, velocity, and acceleration
278  bool success_vel = spline->get_velocity(desired_time, R_GtoI, p_IinG, w_IinI, v_IinG);
279 
280  // Find the bounding bias values
281  bool success_bias = false;
282  size_t id_loc = 0;
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) {
285  id_loc = i;
286  success_bias = true;
287  break;
288  }
289  }
290 
291  // If failed, then that means we don't have any more spline or bias
292  if (!success_vel || !success_bias) {
293  return false;
294  }
295 
296  // Interpolate our biases (they will be at every IMU timestep)
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);
300 
301  // Finally lets create the current state
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;
308  return true;
309 }
310 
311 bool Simulator::get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am) {
312 
313  // Return if the camera measurement should go before us
314  if (timestamp_last_cam + 1.0 / params.sim_freq_cam < timestamp_last_imu + 1.0 / params.sim_freq_imu)
315  return false;
316 
317  // Else lets do a new measurement!!!
318  timestamp_last_imu += 1.0 / params.sim_freq_imu;
319  timestamp = timestamp_last_imu;
320  time_imu = timestamp_last_imu;
321 
322  // Current state values
323  Eigen::Matrix3d R_GtoI;
324  Eigen::Vector3d p_IinG, w_IinI, v_IinG, alpha_IinI, a_IinG;
325 
326  // Get the pose, velocity, and acceleration
327  // NOTE: we get the acceleration between our two IMU
328  // NOTE: this is because we are using a constant measurement model for integration
329  // bool success_accel = spline->get_acceleration(timestamp+0.5/freq_imu, R_GtoI, 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);
331 
332  // If failed, then that means we don't have any more spline
333  // Thus we should stop the simulation
334  if (!success_accel) {
335  is_running = false;
336  return false;
337  }
338 
339  // Transform omega and linear acceleration into imu frame
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;
344 
345  // Get our imu intrinsic parameters
346  // - kalibr: lower triangular of the matrix is used
347  // - rpng: upper triangular of the matrix is used
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);
351 
352  // Get the readings with the imu intrinsic "distortion"
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;
357 
358  // Calculate the bias values for this IMU reading
359  // NOTE: we skip the first ever bias since we have already appended it
360  double dt = 1.0 / params.sim_freq_imu;
361  std::normal_distribution<double> w(0, 1);
362  if (has_skipped_first_bias) {
363 
364  // Move the biases forward in time
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);
371 
372  // Append the current true bias to our history
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);
376  }
377  has_skipped_first_bias = true;
378 
379  // Now add noise to these measurements
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);
386 
387  // Return success
388  return true;
389 }
390 
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) {
393 
394  // Return if the imu measurement should go before us
395  if (timestamp_last_imu + 1.0 / params.sim_freq_imu < timestamp_last_cam + 1.0 / params.sim_freq_cam)
396  return false;
397 
398  // Else lets do a new measurement!!!
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;
402 
403  // Get the pose at the current timestep
404  Eigen::Matrix3d R_GtoI;
405  Eigen::Vector3d p_IinG;
406  bool success_pose = spline->get_pose(timestamp, R_GtoI, p_IinG);
407 
408  // We have finished generating measurements
409  if (!success_pose) {
410  is_running = false;
411  return false;
412  }
413 
414  // Loop through each camera
415  for (int i = 0; i < params.state_options.num_cameras; i++) {
416 
417  // Get the uv features for this frame
418  std::vector<std::pair<size_t, Eigen::VectorXf>> uvs = project_pointcloud(R_GtoI, p_IinG, i, featmap);
419 
420  // If we do not have enough, generate more
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(),
423  params.num_pts);
424  }
425 
426  // If greater than only select the first set
427  if ((int)uvs.size() > params.num_pts) {
428  uvs.erase(uvs.begin() + params.num_pts, uvs.end());
429  }
430 
431  // Append the map size so all cameras have unique features in them (but the same map)
432  // Only do this if we are not enforcing stereo constraints between all our cameras
433  for (size_t f = 0; f < uvs.size() && !params.use_stereo; f++) {
434  uvs.at(f).first += i * featmap.size();
435  }
436 
437  // Loop through and add noise to each uv measurement
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));
442  }
443 
444  // Push back for this camera
445  feats.push_back(uvs);
446  camids.push_back(i);
447  }
448 
449  // Return success
450  return true;
451 }
452 
453 std::vector<std::pair<size_t, Eigen::VectorXf>> Simulator::project_pointcloud(const Eigen::Matrix3d &R_GtoI, const Eigen::Vector3d &p_IinG,
454  int camid,
455  const std::unordered_map<size_t, Eigen::Vector3d> &feats) {
456 
457  // Assert we have good camera
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);
461 
462  // Grab our extrinsic and intrinsic values
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);
466 
467  // Our projected uv true measurements
468  std::vector<std::pair<size_t, Eigen::VectorXf>> uvs;
469 
470  // Loop through our map
471  for (const auto &feat : feats) {
472 
473  // Transform feature into current camera frame
474  Eigen::Vector3d p_FinI = R_GtoI * (feat.second - p_IinG);
475  Eigen::Vector3d p_FinC = R_ItoC * p_FinI + p_IinC;
476 
477  // Skip cloud if too far away
478  if (p_FinC(2) > params.sim_max_feature_gen_distance || p_FinC(2) < 0.1)
479  continue;
480 
481  // Project to normalized coordinates
482  Eigen::Vector2f uv_norm;
483  uv_norm << (float)(p_FinC(0) / p_FinC(2)), (float)(p_FinC(1) / p_FinC(2));
484 
485  // Distort the normalized coordinates
486  Eigen::Vector2f uv_dist = camera->distort_f(uv_norm);
487 
488  // Check that it is inside our bounds
489  if (uv_dist(0) < 0 || uv_dist(0) > camera->w() || uv_dist(1) < 0 || uv_dist(1) > camera->h()) {
490  continue;
491  }
492 
493  // Else we can add this as a good projection
494  uvs.push_back({feat.first, uv_dist});
495  }
496 
497  // Return our projections
498  return uvs;
499 }
500 
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) {
503 
504  // Assert we have good camera
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);
508 
509  // Grab our extrinsic and intrinsic values
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);
513 
514  // Generate the desired number of features
515  for (int i = 0; i < numpts; i++) {
516 
517  // Uniformly randomly generate within our fov
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);
522 
523  // Convert to opencv format
524  cv::Point2f uv_dist((float)u_dist, (float)v_dist);
525 
526  // Undistort this point to our normalized coordinates
527  cv::Point2f uv_norm = camera->undistort_cv(uv_dist);
528 
529  // Generate a random depth
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);
532 
533  // Get the 3d point
534  Eigen::Vector3d bearing;
535  bearing << uv_norm.x, uv_norm.y, 1;
536  Eigen::Vector3d p_FinC;
537  p_FinC = depth * bearing;
538 
539  // Move to the global frame of reference
540  Eigen::Vector3d p_FinI = R_ItoC.transpose() * (p_FinC - p_IinC);
541  Eigen::Vector3d p_FinG = R_GtoI.transpose() * p_FinI + p_IinG;
542 
543  // Append this as a new feature
544  featmap.insert({id_map, p_FinG});
545  id_map++;
546  }
547 }
ov_msckf::VioManagerOptions::camera_extrinsics
std::map< size_t, Eigen::VectorXd > camera_extrinsics
Map between camid and camera extrinsics (q_ItoC, p_IinC).
Definition: VioManagerOptions.h:214
ov_core::DatasetReader::load_simulated_trajectory
static void load_simulated_trajectory(std::string path, std::vector< Eigen::VectorXd > &traj_data)
YELLOW
YELLOW
ov_msckf::VioManagerOptions::camera_intrinsics
std::unordered_map< size_t, std::shared_ptr< ov_core::CamBase > > camera_intrinsics
Map between camid and camera intrinsics (fx, fy, cx, cy, d1...d4, cam_w, cam_h)
Definition: VioManagerOptions.h:211
PRINT_DEBUG
#define PRINT_DEBUG(x...)
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::VioManagerOptions::vec_dw
Eigen::Matrix< double, 6, 1 > vec_dw
Gyroscope IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse)
Definition: VioManagerOptions.h:193
BsplineSE3.h
PRINT_ERROR
#define PRINT_ERROR(x...)
f
f
ov_msckf::StateOptions::do_calib_imu_intrinsics
bool do_calib_imu_intrinsics
Bool to determine whether or not to calibrate the IMU intrinsics.
Definition: StateOptions.h:56
ov_core::exp_so3
Eigen::Matrix< double, 3, 3 > exp_so3(const Eigen::Matrix< double, 3, 1 > &w)
CamRadtan.h
ov_msckf::VioManagerOptions::calib_camimu_dt
double calib_camimu_dt
Time offset between camera and IMU.
Definition: VioManagerOptions.h:208
ov_core::rot_2_quat
Eigen::Matrix< double, 4, 1 > rot_2_quat(const Eigen::Matrix< double, 3, 3 > &rot)
ov_core::quat_2_Rot
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
ov_msckf::VioManagerOptions::q_ACCtoIMU
Eigen::Matrix< double, 4, 1 > q_ACCtoIMU
Rotation from gyroscope frame to the "IMU" accelerometer frame.
Definition: VioManagerOptions.h:202
CamEqui.h
colors.h
ov_msckf::VioManagerOptions::vec_tg
Eigen::Matrix< double, 9, 1 > vec_tg
Gyroscope gravity sensitivity (scale imperfection and axis misalignment, column-wise)
Definition: VioManagerOptions.h:199
ov_msckf::StateOptions::imu_model
ImuModel imu_model
What model our IMU intrinsics are.
Definition: StateOptions.h:65
ov_msckf::VioManagerOptions::q_GYROtoIMU
Eigen::Matrix< double, 4, 1 > q_GYROtoIMU
Rotation from accelerometer to the "IMU" gyroscope frame frame.
Definition: VioManagerOptions.h:205
RESET
#define RESET
dataset_reader.h
ov_msckf::VioManagerOptions::state_options
StateOptions state_options
Core state options (e.g. number of cameras, use fej, stereo, what calibration to enable etc)
Definition: VioManagerOptions.h:74
ov_msckf::VioManagerOptions
Struct which stores all options needed for state estimation.
Definition: VioManagerOptions.h:56
ov_msckf::StateOptions::num_cameras
int num_cameras
Number of distinct cameras that we will observe features in.
Definition: StateOptions.h:83
CamBase.h
State.h
ov_msckf::VioManagerOptions::vec_da
Eigen::Matrix< double, 6, 1 > vec_da
Accelerometer IMU intrinsics (scale imperfection and axis misalignment, column-wise,...
Definition: VioManagerOptions.h:196
ov_msckf::StateOptions::do_calib_imu_g_sensitivity
bool do_calib_imu_g_sensitivity
Bool to determine whether or not to calibrate the Gravity sensitivity.
Definition: StateOptions.h:59
Simulator.h
ov_core
RED
RED
PRINT_WARNING
#define PRINT_WARNING(x...)


ov_msckf
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54