test_dynamic_mle.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 <cmath>
23 #include <csignal>
24 #include <deque>
25 #include <iomanip>
26 #include <sstream>
27 #include <unistd.h>
28 #include <vector>
29 
30 #include <ceres/ceres.h>
31 
32 #include <boost/date_time/posix_time/posix_time.hpp>
33 #include <boost/filesystem.hpp>
34 
35 #if ROS_AVAILABLE == 1
36 #include <nav_msgs/Path.h>
37 #include <ros/ros.h>
38 #include <sensor_msgs/PointCloud.h>
39 #include <sensor_msgs/PointCloud2.h>
41 #endif
42 
45 #include "ceres/Factor_ImuCPIv1.h"
48 #include "sim/SimulatorInit.h"
49 #include "utils/helper.h"
50 
51 #include "types/IMU.h"
52 #include "types/PoseJPL.h"
53 #include "utils/colors.h"
54 #include "utils/sensor_data.h"
55 
56 using namespace ov_init;
57 
58 // Define the function to be called when ctrl-c (SIGINT) is sent to process
59 void signal_callback_handler(int signum) { std::exit(signum); }
60 
61 // Main function
62 int main(int argc, char **argv) {
63 
64  // Ensure we have a path, if the user passes it then we should use it
65  std::string config_path = "unset_path_to_config.yaml";
66  if (argc > 1) {
67  config_path = argv[1];
68  }
69 
70 #if ROS_AVAILABLE == 1
71  // Launch our ros node
72  ros::init(argc, argv, "test_dynamic_mle");
73  auto nh = std::make_shared<ros::NodeHandle>("~");
74  nh->param<std::string>("config_path", config_path, config_path);
75 
76  // Topics to publish
77  auto pub_pathimu = nh->advertise<nav_msgs::Path>("/ov_msckf/pathimu", 2);
78  PRINT_DEBUG("Publishing: %s\n", pub_pathimu.getTopic().c_str());
79  auto pub_pathgt = nh->advertise<nav_msgs::Path>("/ov_msckf/pathgt", 2);
80  PRINT_DEBUG("Publishing: %s\n", pub_pathgt.getTopic().c_str());
81  auto pub_loop_point = nh->advertise<sensor_msgs::PointCloud>("/ov_msckf/loop_feats", 2);
82  PRINT_DEBUG("Publishing: %s\n", pub_loop_point.getTopic().c_str());
83  auto pub_points_sim = nh->advertise<sensor_msgs::PointCloud2>("/ov_msckf/points_sim", 2);
84  PRINT_DEBUG("Publishing: %s\n", pub_points_sim.getTopic().c_str());
85 #endif
86 
87  // Load the config
88  auto parser = std::make_shared<ov_core::YamlParser>(config_path);
89 #if ROS_AVAILABLE == 1
90  parser->set_node_handler(nh);
91 #endif
92 
93  // Verbosity
94  std::string verbosity = "INFO";
95  parser->parse_config("verbosity", verbosity);
97 
98  // Create the simulator
100  params.print_and_load(parser);
101  params.print_and_load_simulation(parser);
102  if (!parser->successful()) {
103  PRINT_ERROR(RED "unable to parse all parameters, please fix\n" RESET);
104  std::exit(EXIT_FAILURE);
105  }
106  SimulatorInit sim(params);
107 
108  //===================================================================================
109  //===================================================================================
110  //===================================================================================
111 
112  // Ceres problem stuff
113  // NOTE: By default the problem takes ownership of the memory
114  ceres::Problem problem;
115 
116  // Our system states (map from time to index)
117  std::map<double, int> map_states;
118  std::vector<double *> ceres_vars_ori;
119  std::vector<double *> ceres_vars_pos;
120  std::vector<double *> ceres_vars_vel;
121  std::vector<double *> ceres_vars_bias_g;
122  std::vector<double *> ceres_vars_bias_a;
123 
124  // Feature states (3dof p_FinG)
125  std::map<size_t, int> map_features;
126  std::vector<double *> ceres_vars_feat;
127  typedef std::vector<std::pair<Factor_ImageReprojCalib *, std::vector<double *>>> factpair;
128  std::map<size_t, factpair> map_features_delayed; // only valid as long as problem is
129 
130  // Setup extrinsic calibration q_ItoC, p_IinC (map from camera id to index)
131  std::map<size_t, int> map_calib_cam2imu;
132  std::vector<double *> ceres_vars_calib_cam2imu_ori;
133  std::vector<double *> ceres_vars_calib_cam2imu_pos;
134 
135  // Setup intrinsic calibration focal, center, distortion (map from camera id to index)
136  std::map<size_t, int> map_calib_cam;
137  std::vector<double *> ceres_vars_calib_cam_intrinsics;
138 
139  // Set the optimization settings
140  // NOTE: We use dense schur since after eliminating features we have a dense problem
141  // NOTE: http://ceres-solver.org/solving_faqs.html#solving
142  ceres::Solver::Options options;
143  options.linear_solver_type = ceres::DENSE_SCHUR;
144  options.trust_region_strategy_type = ceres::DOGLEG;
145  // options.linear_solver_type = ceres::SPARSE_SCHUR;
146  // options.trust_region_strategy_type = ceres::LEVENBERG_MARQUARDT;
147  options.num_threads = 6;
148  options.max_solver_time_in_seconds = 9999;
149  options.max_num_iterations = 20;
150  options.minimizer_progress_to_stdout = true;
151  // options.use_nonmonotonic_steps = true;
152  // options.function_tolerance = 1e-5;
153  // options.gradient_tolerance = 1e-4 * options.function_tolerance;
154 
155  // DEBUG: check analytical jacobians using ceres finite differences
156  // options.check_gradients = true;
157  // options.gradient_check_relative_precision = 1e-4;
158  // options.gradient_check_numeric_derivative_relative_step_size = 1e-8;
159 
160  //===================================================================================
161  //===================================================================================
162  //===================================================================================
163 
164  // Random number generator used to perturb the groundtruth features
165  // NOTE: It seems that if this too large it can really prevent good optimization
166  // NOTE: Values greater 5cm seems to fail, not sure if this is reasonable or not...
167  std::mt19937 gen_state_perturb(params.sim_seed_preturb);
168  double feat_noise = 0.05; // meters
169 
170  // Buffer our camera image
171  double buffer_timecam = -1;
172  double buffer_timecam_last = -1;
173  std::vector<int> buffer_camids;
174  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> buffer_feats;
175  auto imu_readings = std::make_shared<std::vector<ov_core::ImuData>>();
176 
177  // Simulate!
178  signal(SIGINT, signal_callback_handler);
179  while (sim.ok()) {
180 
181  // IMU: get the next simulated IMU measurement if we have it
182  ov_core::ImuData message_imu;
183  bool hasimu = sim.get_next_imu(message_imu.timestamp, message_imu.wm, message_imu.am);
184  if (hasimu) {
185  imu_readings->push_back(message_imu);
186  }
187 
188  // CAM: get the next simulated camera uv measurements if we have them
189  double time_cam;
190  std::vector<int> camids;
191  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> feats;
192  bool hascam = sim.get_next_cam(time_cam, camids, feats);
193  if (hascam) {
194  if (buffer_timecam != -1) {
195 
196  // Get our predicted state at the requested camera timestep
197  double timestamp_k = buffer_timecam_last;
198  double timestamp_k1 = buffer_timecam;
199  Eigen::Matrix<double, 16, 1> state_k1;
200  std::shared_ptr<ov_core::CpiV1> cpi = nullptr;
201  if (map_states.empty()) {
202 
203  // Add the first ever pose to the problem
204  // TODO: do not initialize from the groundtruth pose
205  double time1 = timestamp_k1 + sim.get_true_parameters().calib_camimu_dt;
206  Eigen::Matrix<double, 17, 1> gt_imustate;
207  bool success = sim.get_state(time1, gt_imustate);
208  assert(success);
209  state_k1 = gt_imustate.block(1, 0, 16, 1);
210 
211  } else {
212 
213  // Get our previous state timestamp (newest time) and biases to integrate with
214  assert(timestamp_k != -1);
215  Eigen::Vector4d quat_k;
216  for (int i = 0; i < 4; i++) {
217  quat_k(i) = ceres_vars_ori.at(map_states.at(timestamp_k))[i];
218  }
219  Eigen::Vector3d pos_k, vel_k, bias_g_k, bias_a_k;
220  for (int i = 0; i < 3; i++) {
221  pos_k(i) = ceres_vars_pos.at(map_states.at(timestamp_k))[i];
222  vel_k(i) = ceres_vars_vel.at(map_states.at(timestamp_k))[i];
223  bias_g_k(i) = ceres_vars_bias_g.at(map_states.at(timestamp_k))[i];
224  bias_a_k(i) = ceres_vars_bias_a.at(map_states.at(timestamp_k))[i];
225  }
226  Eigen::Vector3d gravity;
227  gravity << 0.0, 0.0, params.gravity_mag;
228 
229  // Preintegrate from previous state
230  // Then append a new state with preintegration factor
231  // TODO: estimate the timeoffset? don't use the true?
232  double time0 = timestamp_k + sim.get_true_parameters().calib_camimu_dt;
233  double time1 = timestamp_k1 + sim.get_true_parameters().calib_camimu_dt;
234  auto readings = InitializerHelper::select_imu_readings(*imu_readings, time0, time1);
235  cpi = std::make_shared<ov_core::CpiV1>(params.sigma_w, params.sigma_wb, params.sigma_a, params.sigma_ab, false);
236  cpi->setLinearizationPoints(bias_g_k, bias_a_k, quat_k, gravity);
237  for (size_t k = 0; k < readings.size() - 1; k++) {
238  auto imu0 = readings.at(k);
239  auto imu1 = readings.at(k + 1);
240  cpi->feed_IMU(imu0.timestamp, imu1.timestamp, imu0.wm, imu0.am, imu1.wm, imu1.am);
241  }
242  assert(timestamp_k1 > timestamp_k);
243 
244  // Compute the predicted state
245  state_k1.block(0, 0, 4, 1) = ov_core::quat_multiply(cpi->q_k2tau, quat_k);
246  state_k1.block(4, 0, 3, 1) =
247  pos_k + vel_k * cpi->DT - 0.5 * cpi->grav * std::pow(cpi->DT, 2) + ov_core::quat_2_Rot(quat_k).transpose() * cpi->alpha_tau;
248  state_k1.block(7, 0, 3, 1) = vel_k - cpi->grav * cpi->DT + ov_core::quat_2_Rot(quat_k).transpose() * cpi->beta_tau;
249  state_k1.block(10, 0, 3, 1) = bias_g_k;
250  state_k1.block(13, 0, 3, 1) = bias_a_k;
251  }
252 
253  // ================================================================
254  // ADDING GRAPH STATE / ESTIMATES!
255  // ================================================================
256 
257  // Load our state variables into our allocated state pointers
258  auto *var_ori = new double[4];
259  for (int i = 0; i < 4; i++) {
260  var_ori[i] = state_k1(0 + i, 0);
261  }
262  auto *var_pos = new double[3];
263  auto *var_vel = new double[3];
264  auto *var_bias_g = new double[3];
265  auto *var_bias_a = new double[3];
266  for (int i = 0; i < 3; i++) {
267  var_pos[i] = state_k1(4 + i, 0);
268  var_vel[i] = state_k1(7 + i, 0);
269  var_bias_g[i] = state_k1(10 + i, 0);
270  var_bias_a[i] = state_k1(13 + i, 0);
271  }
272 
273  // Now actually create the parameter block in the ceres problem
274  auto ceres_jplquat = new State_JPLQuatLocal();
275  problem.AddParameterBlock(var_ori, 4, ceres_jplquat);
276  problem.AddParameterBlock(var_pos, 3);
277  problem.AddParameterBlock(var_vel, 3);
278  problem.AddParameterBlock(var_bias_g, 3);
279  problem.AddParameterBlock(var_bias_a, 3);
280 
281  // Fix this first ever pose to constrain the problem
282  // On the Comparison of Gauge Freedom Handling in Optimization-Based Visual-Inertial State Estimation
283  // Zichao Zhang; Guillermo Gallego; Davide Scaramuzza
284  // https://ieeexplore.ieee.org/document/8354808
285  if (map_states.empty()) {
286 
287  // Construct state and prior
288  Eigen::MatrixXd x_lin = Eigen::MatrixXd::Zero(7, 1);
289  for (int i = 0; i < 4; i++) {
290  x_lin(0 + i) = var_ori[i];
291  }
292  for (int i = 0; i < 3; i++) {
293  x_lin(4 + i) = var_pos[i];
294  // x_lin(7 + i) = var_bias_g[i];
295  // x_lin(10 + i) = var_bias_a[i];
296  }
297  Eigen::MatrixXd prior_grad = Eigen::MatrixXd::Zero(4, 1);
298  Eigen::MatrixXd prior_Info = Eigen::MatrixXd::Identity(4, 4);
299  prior_Info.block(0, 0, 4, 4) *= 1.0 / std::pow(1e-8, 2); // 4dof unobservable yaw and position
300  // prior_Info.block(4, 4, 3, 3) *= 1.0 / std::pow(1e-1, 2); // bias_g prior
301  // prior_Info.block(7, 7, 3, 3) *= 1.0 / std::pow(1e-1, 2); // bias_a prior
302 
303  // Construct state type and ceres parameter pointers
304  std::vector<std::string> x_types;
305  std::vector<double *> factor_params;
306  factor_params.push_back(var_ori);
307  x_types.emplace_back("quat_yaw");
308  factor_params.push_back(var_pos);
309  x_types.emplace_back("vec3");
310  // factor_params.push_back(var_bias_g);
311  // x_types.emplace_back("vec3");
312  // factor_params.push_back(var_bias_a);
313  // x_types.emplace_back("vec3");
314 
315  // Append it to the problem
316  auto *factor_prior = new Factor_GenericPrior(x_lin, x_types, prior_Info, prior_grad);
317  problem.AddResidualBlock(factor_prior, nullptr, factor_params);
318  // problem.SetParameterBlockConstant(var_ori);
319  // problem.SetParameterBlockConstant(var_pos);
320  }
321 
322  // Append to our historical vector of states
323  map_states.insert({timestamp_k1, (int)ceres_vars_ori.size()});
324  ceres_vars_ori.push_back(var_ori);
325  ceres_vars_pos.push_back(var_pos);
326  ceres_vars_vel.push_back(var_vel);
327  ceres_vars_bias_g.push_back(var_bias_g);
328  ceres_vars_bias_a.push_back(var_bias_a);
329  buffer_timecam_last = timestamp_k1;
330 
331  // ================================================================
332  // ADDING GRAPH FACTORS!
333  // ================================================================
334 
335  // Append the new IMU factor
336  if (cpi != nullptr) {
337  assert(timestamp_k != -1);
338  std::vector<double *> factor_params;
339  factor_params.push_back(ceres_vars_ori.at(map_states.at(timestamp_k)));
340  factor_params.push_back(ceres_vars_bias_g.at(map_states.at(timestamp_k)));
341  factor_params.push_back(ceres_vars_vel.at(map_states.at(timestamp_k)));
342  factor_params.push_back(ceres_vars_bias_a.at(map_states.at(timestamp_k)));
343  factor_params.push_back(ceres_vars_pos.at(map_states.at(timestamp_k)));
344  factor_params.push_back(ceres_vars_ori.at(map_states.at(timestamp_k1)));
345  factor_params.push_back(ceres_vars_bias_g.at(map_states.at(timestamp_k1)));
346  factor_params.push_back(ceres_vars_vel.at(map_states.at(timestamp_k1)));
347  factor_params.push_back(ceres_vars_bias_a.at(map_states.at(timestamp_k1)));
348  factor_params.push_back(ceres_vars_pos.at(map_states.at(timestamp_k1)));
349  auto *factor_imu = new Factor_ImuCPIv1(cpi->DT, cpi->grav, cpi->alpha_tau, cpi->beta_tau, cpi->q_k2tau, cpi->b_a_lin,
350  cpi->b_w_lin, cpi->J_q, cpi->J_b, cpi->J_a, cpi->H_b, cpi->H_a, cpi->P_meas);
351  problem.AddResidualBlock(factor_imu, nullptr, factor_params);
352  }
353 
354  // Then, append new feature observations factors seen from this frame (initialize features as needed)
355  // We first loop through each camera and for each we append measurements as needed
356  assert(buffer_camids.size() == buffer_feats.size());
357  for (size_t n = 0; n < buffer_camids.size(); n++) {
358 
359  // First make sure we have calibration states added
360  int cam_id = buffer_camids.at(n);
361  if (map_calib_cam2imu.find(cam_id) == map_calib_cam2imu.end()) {
362  auto *var_calib_ori = new double[4];
363  for (int i = 0; i < 4; i++) {
364  var_calib_ori[i] = params.camera_extrinsics.at(cam_id)(0 + i, 0);
365  }
366  auto *var_calib_pos = new double[3];
367  for (int i = 0; i < 3; i++) {
368  var_calib_pos[i] = params.camera_extrinsics.at(cam_id)(4 + i, 0);
369  }
370  auto ceres_calib_jplquat = new State_JPLQuatLocal();
371  problem.AddParameterBlock(var_calib_ori, 4, ceres_calib_jplquat);
372  problem.AddParameterBlock(var_calib_pos, 3);
373  map_calib_cam2imu.insert({cam_id, (int)ceres_vars_calib_cam2imu_ori.size()});
374  ceres_vars_calib_cam2imu_ori.push_back(var_calib_ori);
375  ceres_vars_calib_cam2imu_pos.push_back(var_calib_pos);
376 
377  // Construct state and prior
378  Eigen::MatrixXd x_lin = Eigen::MatrixXd::Zero(7, 1);
379  for (int i = 0; i < 4; i++) {
380  x_lin(0 + i) = var_calib_ori[i];
381  }
382  for (int i = 0; i < 3; i++) {
383  x_lin(4 + i) = var_calib_pos[i];
384  }
385  Eigen::MatrixXd prior_grad = Eigen::MatrixXd::Zero(6, 1);
386  Eigen::MatrixXd prior_Info = Eigen::MatrixXd::Identity(6, 6);
387  prior_Info.block(0, 0, 3, 3) *= 1.0 / std::pow(0.001, 2);
388  prior_Info.block(3, 3, 3, 3) *= 1.0 / std::pow(0.01, 2);
389 
390  // Construct state type and ceres parameter pointers
391  std::vector<std::string> x_types;
392  std::vector<double *> factor_params;
393  factor_params.push_back(var_calib_ori);
394  x_types.emplace_back("quat");
395  factor_params.push_back(var_calib_pos);
396  x_types.emplace_back("vec3");
397  if (!params.init_dyn_mle_opt_calib) {
398  problem.SetParameterBlockConstant(var_calib_ori);
399  problem.SetParameterBlockConstant(var_calib_pos);
400  } else {
401  auto *factor_prior = new Factor_GenericPrior(x_lin, x_types, prior_Info, prior_grad);
402  problem.AddResidualBlock(factor_prior, nullptr, factor_params);
403  }
404  }
405  bool is_fisheye = (std::dynamic_pointer_cast<ov_core::CamEqui>(params.camera_intrinsics.at(cam_id)) != nullptr);
406  if (map_calib_cam.find(cam_id) == map_calib_cam.end()) {
407  auto *var_calib_cam = new double[8];
408  for (int i = 0; i < 8; i++) {
409  var_calib_cam[i] = params.camera_intrinsics.at(cam_id)->get_value()(i, 0);
410  }
411  problem.AddParameterBlock(var_calib_cam, 8);
412  map_calib_cam.insert({cam_id, (int)ceres_vars_calib_cam_intrinsics.size()});
413  ceres_vars_calib_cam_intrinsics.push_back(var_calib_cam);
414 
415  // Construct state and prior
416  Eigen::MatrixXd x_lin = Eigen::MatrixXd::Zero(8, 1);
417  for (int i = 0; i < 8; i++) {
418  x_lin(0 + i) = var_calib_cam[i];
419  }
420  Eigen::MatrixXd prior_grad = Eigen::MatrixXd::Zero(8, 1);
421  Eigen::MatrixXd prior_Info = Eigen::MatrixXd::Identity(8, 8);
422  prior_Info.block(0, 0, 4, 4) *= 1.0 / std::pow(1.0, 2);
423  prior_Info.block(4, 4, 4, 4) *= 1.0 / std::pow(0.005, 2);
424 
425  // Construct state type and ceres parameter pointers
426  std::vector<std::string> x_types;
427  std::vector<double *> factor_params;
428  factor_params.push_back(var_calib_cam);
429  x_types.emplace_back("vec8");
430  if (!params.init_dyn_mle_opt_calib) {
431  problem.SetParameterBlockConstant(var_calib_cam);
432  } else {
433  auto *factor_prior = new Factor_GenericPrior(x_lin, x_types, prior_Info, prior_grad);
434  problem.AddResidualBlock(factor_prior, nullptr, factor_params);
435  }
436  }
437 
438  // Now loop through each feature observed at this k+1 timestamp
439  for (auto const &feat : buffer_feats.at(n)) {
440  size_t featid = feat.first;
441  Eigen::Vector2d uv_raw;
442  uv_raw << feat.second(0), feat.second(1);
443 
444  // Next make sure that we have the feature state
445  // Normally, we should need to triangulate this once we have enough measurements
446  // TODO: do not initialize features from the groundtruth map
447  if (map_features.find(featid) == map_features.end()) {
448  assert(params.use_stereo);
449  Eigen::Vector3d p_FinG = sim.get_map().at(featid);
450  auto *var_feat = new double[3];
451  for (int i = 0; i < 3; i++) {
452  std::normal_distribution<double> w(0, 1);
453  var_feat[i] = p_FinG(i) + feat_noise * w(gen_state_perturb);
454  }
455  map_features.insert({featid, (int)ceres_vars_feat.size()});
456  map_features_delayed.insert({featid, factpair()});
457  ceres_vars_feat.push_back(var_feat);
458  }
459 
460  // Factor parameters it is a function of
461  std::vector<double *> factor_params;
462  factor_params.push_back(ceres_vars_ori.at(map_states.at(timestamp_k1)));
463  factor_params.push_back(ceres_vars_pos.at(map_states.at(timestamp_k1)));
464  factor_params.push_back(ceres_vars_feat.at(map_features.at(featid)));
465  factor_params.push_back(ceres_vars_calib_cam2imu_ori.at(map_calib_cam2imu.at(cam_id)));
466  factor_params.push_back(ceres_vars_calib_cam2imu_pos.at(map_calib_cam2imu.at(cam_id)));
467  factor_params.push_back(ceres_vars_calib_cam_intrinsics.at(map_calib_cam.at(cam_id)));
468  auto *factor_pinhole = new Factor_ImageReprojCalib(uv_raw, params.sigma_pix, is_fisheye);
469  if (map_features_delayed.find(featid) != map_features_delayed.end()) {
470  map_features_delayed.at(featid).push_back({factor_pinhole, factor_params});
471  } else {
472  ceres::LossFunction *loss_function = nullptr;
473  // ceres::LossFunction *loss_function = new ceres::CauchyLoss(1.0);
474  problem.AddResidualBlock(factor_pinhole, loss_function, factor_params);
475  }
476  }
477  }
478  }
479  buffer_timecam = time_cam;
480  buffer_camids = camids;
481  buffer_feats = feats;
482 
483  // If a delayed feature has enough measurements we can add it to the problem!
484  // We will wait for enough observations before adding the parameter
485  // This should make it much more stable since the parameter / optimization is more constrained
486  size_t min_num_meas_to_optimize = 10;
487  auto it0 = map_features_delayed.begin();
488  while (it0 != map_features_delayed.end()) {
489  size_t featid = (*it0).first;
490  auto factors = (*it0).second;
491  if (factors.size() >= min_num_meas_to_optimize) {
492  problem.AddParameterBlock(ceres_vars_feat.at(map_features.at(featid)), 3);
493  for (auto const &factorpair : factors) {
494  auto factor_pinhole = factorpair.first;
495  auto factor_params = factorpair.second;
496  ceres::LossFunction *loss_function = nullptr;
497  // ceres::LossFunction *loss_function = new ceres::CauchyLoss(1.0);
498  problem.AddResidualBlock(factor_pinhole, loss_function, factor_params);
499  }
500  it0 = map_features_delayed.erase(it0);
501  } else {
502  it0++;
503  }
504  }
505 
506  // ================================================================
507  // PERFORM ACTUAL OPTIMIZATION!
508  // ================================================================
509 
510  // We can try to optimize every few frames, but this can cause the IMU to drift
511  // Thus this can't be too large, nor too small to reduce the computation
512  if (map_states.size() % 10 == 0 && map_states.size() > min_num_meas_to_optimize) {
513 
514  // COMPUTE: error before optimization
515  double error_before = 0.0;
516  if (!map_features.empty()) {
517  for (auto &feat : map_features) {
518  Eigen::Vector3d pos1, pos2;
519  pos1 << ceres_vars_feat.at(feat.second)[0], ceres_vars_feat.at(feat.second)[1], ceres_vars_feat.at(feat.second)[2];
520  pos2 = sim.get_map().at(feat.first);
521  error_before += (pos2 - pos1).norm();
522  }
523  error_before /= (double)map_features.size();
524  }
525 
526  // Optimize the ceres graph
527  ceres::Solver::Summary summary;
528  ceres::Solve(options, &problem, &summary);
529  PRINT_INFO("[CERES]: %s\n", summary.message.c_str());
530  PRINT_INFO("[CERES]: %d iterations | %zu states, %zu features | %d parameters and %d residuals | cost %.4e => %.4e\n",
531  (int)summary.iterations.size(), map_states.size(), map_features.size(), summary.num_parameters, summary.num_residuals,
532  summary.initial_cost, summary.final_cost);
533 
534  // COMPUTE: error after optimization
535  double error_after = 0.0;
536  if (!map_features.empty()) {
537  for (auto &feat : map_features) {
538  Eigen::Vector3d pos1, pos2;
539  pos1 << ceres_vars_feat.at(feat.second)[0], ceres_vars_feat.at(feat.second)[1], ceres_vars_feat.at(feat.second)[2];
540  pos2 = sim.get_map().at(feat.first);
541  error_after += (pos2 - pos1).norm();
542  }
543  error_after /= (double)map_features.size();
544  }
545  PRINT_INFO("[CERES]: map error %.4f => %.4f (meters) for %zu features\n", error_before, error_after, map_features.size());
546 
547  // Print feature positions to console
548  // https://gist.github.com/goldbattle/177a6b2cccb4b4208e687b0abae4bc9f
549  // for (auto &feat : map_features) {
550  // size_t featid = feat.first;
551  // std::cout << featid << ",";
552  // std::cout << ceres_vars_feat[map_features[featid]][0] << "," << ceres_vars_feat[map_features[featid]][1] << ","
553  // << ceres_vars_feat[map_features[featid]][2] << ",";
554  // std::cout << sim.get_map().at(featid)[0] << "," << sim.get_map().at(featid)[1] << "," << sim.get_map().at(featid)[2] <<
555  // ","; std::cout << map_features_num_meas[feat.first] << ";" << std::endl;
556  // }
557  }
558 
559 #if ROS_AVAILABLE == 1
560  // Visualize in RVIZ our current estimates and
561  if (map_states.size() % 1 == 0) {
562 
563  // Pose states
564  nav_msgs::Path arrEST, arrGT;
565  arrEST.header.stamp = ros::Time::now();
566  arrEST.header.frame_id = "global";
567  arrGT.header.stamp = ros::Time::now();
568  arrGT.header.frame_id = "global";
569  for (auto &statepair : map_states) {
570  geometry_msgs::PoseStamped poseEST, poseGT;
571  poseEST.header.stamp = ros::Time(statepair.first);
572  poseEST.header.frame_id = "global";
573  poseEST.pose.orientation.x = ceres_vars_ori[statepair.second][0];
574  poseEST.pose.orientation.y = ceres_vars_ori[statepair.second][1];
575  poseEST.pose.orientation.z = ceres_vars_ori[statepair.second][2];
576  poseEST.pose.orientation.w = ceres_vars_ori[statepair.second][3];
577  poseEST.pose.position.x = ceres_vars_pos[statepair.second][0];
578  poseEST.pose.position.y = ceres_vars_pos[statepair.second][1];
579  poseEST.pose.position.z = ceres_vars_pos[statepair.second][2];
580  Eigen::Matrix<double, 17, 1> gt_imustate;
581  bool success = sim.get_state(statepair.first + sim.get_true_parameters().calib_camimu_dt, gt_imustate);
582  assert(success);
583  poseGT.header.stamp = ros::Time(statepair.first);
584  poseGT.header.frame_id = "global";
585  poseGT.pose.orientation.x = gt_imustate(1);
586  poseGT.pose.orientation.y = gt_imustate(2);
587  poseGT.pose.orientation.z = gt_imustate(3);
588  poseGT.pose.orientation.w = gt_imustate(4);
589  poseGT.pose.position.x = gt_imustate(5);
590  poseGT.pose.position.y = gt_imustate(6);
591  poseGT.pose.position.z = gt_imustate(7);
592  arrEST.poses.push_back(poseEST);
593  arrGT.poses.push_back(poseGT);
594  }
595  pub_pathimu.publish(arrEST);
596  pub_pathgt.publish(arrGT);
597 
598  // Features ESTIMATES pointcloud
599  sensor_msgs::PointCloud point_cloud;
600  point_cloud.header.frame_id = "global";
601  point_cloud.header.stamp = ros::Time::now();
602  for (auto &featpair : map_features) {
603  if (map_features_delayed.find(featpair.first) != map_features_delayed.end())
604  continue;
605  geometry_msgs::Point32 p;
606  p.x = (float)ceres_vars_feat[map_features[featpair.first]][0];
607  p.y = (float)ceres_vars_feat[map_features[featpair.first]][1];
608  p.z = (float)ceres_vars_feat[map_features[featpair.first]][2];
609  point_cloud.points.push_back(p);
610  }
611  pub_loop_point.publish(point_cloud);
612 
613  // Features GROUNDTRUTH pointcloud
614  sensor_msgs::PointCloud2 cloud;
615  cloud.header.frame_id = "global";
616  cloud.header.stamp = ros::Time::now();
617  cloud.width = map_features.size();
618  cloud.height = 1;
619  cloud.is_bigendian = false;
620  cloud.is_dense = false; // there may be invalid points
621  sensor_msgs::PointCloud2Modifier modifier(cloud);
622  modifier.setPointCloud2FieldsByString(1, "xyz");
623  modifier.resize(map_features.size());
624  sensor_msgs::PointCloud2Iterator<float> out_x(cloud, "x");
625  sensor_msgs::PointCloud2Iterator<float> out_y(cloud, "y");
626  sensor_msgs::PointCloud2Iterator<float> out_z(cloud, "z");
627  for (auto &featpair : map_features) {
628  if (map_features_delayed.find(featpair.first) != map_features_delayed.end())
629  continue;
630  *out_x = (float)sim.get_map().at(featpair.first)(0); // no change in id since no tracker is used
631  ++out_x;
632  *out_y = (float)sim.get_map().at(featpair.first)(1); // no change in id since no tracker is used
633  ++out_y;
634  *out_z = (float)sim.get_map().at(featpair.first)(2); // no change in id since no tracker is used
635  ++out_z;
636  }
637  pub_points_sim.publish(cloud);
638  }
639 #endif
640  }
641  }
642 
643  // Done!
644  return EXIT_SUCCESS;
645 };
point_cloud2_iterator.h
ov_init::InertialInitializerOptions::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: InertialInitializerOptions.h:249
ov_init::InertialInitializerOptions::sigma_pix
double sigma_pix
Noise sigma for our raw pixel measurements.
Definition: InertialInitializerOptions.h:207
ov_init::InertialInitializerOptions
Struct which stores all options needed for state estimation.
Definition: InertialInitializerOptions.h:49
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
SimulatorInit.h
ov_init::InertialInitializerOptions::camera_extrinsics
std::map< size_t, Eigen::VectorXd > camera_extrinsics
Map between camid and camera extrinsics (q_ItoC, p_IinC).
Definition: InertialInitializerOptions.h:252
ov_init::InertialInitializerOptions::print_and_load_simulation
void print_and_load_simulation(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all simulated parameters. This allows for visual checking that ever...
Definition: InertialInitializerOptions.h:388
IMU.h
ros.h
ov_core::quat_multiply
Eigen::Matrix< double, 4, 1 > quat_multiply(const Eigen::Matrix< double, 4, 1 > &q, const Eigen::Matrix< double, 4, 1 > &p)
PRINT_DEBUG
#define PRINT_DEBUG(x...)
sensor_data.h
ov_init::InertialInitializerOptions::sigma_w
double sigma_w
Gyroscope white noise (rad/s/sqrt(hz))
Definition: InertialInitializerOptions.h:195
ov_init::InertialInitializerOptions::gravity_mag
double gravity_mag
Gravity magnitude in the global frame (i.e. should be 9.81 typically)
Definition: InertialInitializerOptions.h:234
PRINT_ERROR
#define PRINT_ERROR(x...)
ov_init::InertialInitializerOptions::sigma_ab
double sigma_ab
Accelerometer random walk (m/s^3/sqrt(hz))
Definition: InertialInitializerOptions.h:204
ov_init::SimulatorInit::get_map
std::unordered_map< size_t, Eigen::Vector3d > get_map()
Returns the true 3d map of features.
Definition: SimulatorInit.h:106
ov_init::SimulatorInit::get_next_imu
bool get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am)
Gets the next inertial reading if we have one.
Definition: SimulatorInit.cpp:289
ov_init::SimulatorInit::ok
bool ok()
Returns if we are actively simulating.
Definition: SimulatorInit.h:71
sensor_msgs::PointCloud2Iterator
PoseJPL.h
Factor_ImuCPIv1.h
ov_init::Factor_GenericPrior
Factor for generic state priors for specific types.
Definition: Factor_GenericPrior.h:72
ov_core::Printer::setPrintLevel
static void setPrintLevel(const std::string &level)
ov_init::InertialInitializerOptions::print_and_load
void print_and_load(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load the non-simulation parameters of the system and print.
Definition: InertialInitializerOptions.h:55
ov_init::InertialInitializerOptions::calib_camimu_dt
double calib_camimu_dt
Time offset between camera and IMU (t_imu = t_cam + t_off)
Definition: InertialInitializerOptions.h:246
ov_init::Factor_ImuCPIv1
Factor for IMU continuous preintegration version 1.
Definition: Factor_ImuCPIv1.h:32
ov_init::InertialInitializerOptions::init_dyn_mle_opt_calib
bool init_dyn_mle_opt_calib
If we should optimize and recover the calibration in our MLE.
Definition: InertialInitializerOptions.h:79
ov_init::SimulatorInit::get_next_cam
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.
Definition: SimulatorInit.cpp:350
ov_init
State initialization code.
Definition: Factor_GenericPrior.h:27
ov_core::ImuData::wm
Eigen::Matrix< double, 3, 1 > wm
ov_core::ImuData
ov_core::quat_2_Rot
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
ov_init::InitializerHelper::select_imu_readings
static std::vector< ov_core::ImuData > select_imu_readings(const std::vector< ov_core::ImuData > &imu_data_tmp, double time0, double time1)
Helper function that given current imu data, will select imu readings between the two times.
Definition: helper.h:66
ov_init::InertialInitializerOptions::use_stereo
bool use_stereo
If we should process two cameras are being stereo or binocular. If binocular, we do monocular feature...
Definition: InertialInitializerOptions.h:240
Factor_GenericPrior.h
main
int main(int argc, char **argv)
Definition: test_dynamic_mle.cpp:62
State_JPLQuatLocal.h
ov_init::SimulatorInit::get_true_parameters
InertialInitializerOptions get_true_parameters()
Access function to get the true parameters (i.e. calibration and settings)
Definition: SimulatorInit.h:109
ov_core::ImuData::am
Eigen::Matrix< double, 3, 1 > am
sensor_msgs::PointCloud2Modifier::resize
void resize(size_t size)
ros::Time
colors.h
sensor_msgs::PointCloud2Modifier
PRINT_INFO
#define PRINT_INFO(x...)
ov_init::InertialInitializerOptions::sim_seed_preturb
int sim_seed_preturb
Seed for calibration perturbations. Change this to perturb by different random values if perturbation...
Definition: InertialInitializerOptions.h:354
RESET
#define RESET
ov_init::Factor_ImageReprojCalib
Factor of feature bearing observation (raw) with calibration.
Definition: Factor_ImageReprojCalib.h:41
signal_callback_handler
void signal_callback_handler(int signum)
Definition: test_dynamic_mle.cpp:59
ov_init::SimulatorInit
Master simulator class that generated visual-inertial measurements.
Definition: SimulatorInit.h:52
ov_init::State_JPLQuatLocal
JPL quaternion CERES state parameterization.
Definition: State_JPLQuatLocal.h:32
ov_init::InertialInitializerOptions::sigma_a
double sigma_a
Accelerometer white noise (m/s^2/sqrt(hz))
Definition: InertialInitializerOptions.h:201
Factor_ImageReprojCalib.h
InertialInitializerOptions.h
helper.h
ov_core::ImuData::timestamp
double timestamp
RED
RED
ov_init::InertialInitializerOptions::sigma_wb
double sigma_wb
Gyroscope random walk (rad/s^2/sqrt(hz))
Definition: InertialInitializerOptions.h:198
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
ov_init::SimulatorInit::get_state
bool get_state(double desired_time, Eigen::Matrix< double, 17, 1 > &imustate)
Get the simulation state at a specified timestep.
Definition: SimulatorInit.cpp:245
ros::Time::now
static Time now()


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