test_sim_repeat.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 <sstream>
26 #include <unistd.h>
27 #include <vector>
28 
29 #include <boost/date_time/posix_time/posix_time.hpp>
30 #include <boost/filesystem.hpp>
31 
32 #if ROS_AVAILABLE == 1
33 #include <ros/ros.h>
34 #endif
35 
36 #include "core/VioManagerOptions.h"
37 #include "sim/Simulator.h"
38 #include "utils/print.h"
39 
40 using namespace ov_msckf;
41 
42 // Define the function to be called when ctrl-c (SIGINT) is sent to process
43 void signal_callback_handler(int signum) { std::exit(signum); }
44 
45 // Main function
46 int main(int argc, char **argv) {
47 
48  // Register failure handler
49  signal(SIGINT, signal_callback_handler);
50 
51  // Ensure we have a path, if the user passes it then we should use it
52  std::string config_path = "unset_path_to_config.yaml";
53  if (argc > 1) {
54  config_path = argv[1];
55  }
56 
57 #if ROS_AVAILABLE == 1
58  // Launch our ros node
59  ros::init(argc, argv, "test_sim_repeat");
60  auto nh = std::make_shared<ros::NodeHandle>("~");
61  nh->param<std::string>("config_path", config_path, config_path);
62 #endif
63 
64  // Load the config
65  auto parser = std::make_shared<ov_core::YamlParser>(config_path);
66 #if ROS_AVAILABLE == 1
67  parser->set_node_handler(nh);
68 #endif
69 
70  // Verbosity
71  std::string verbosity = "INFO";
72  parser->parse_config("verbosity", verbosity);
74 
75  //===================================================
76  //===================================================
77 
78  // Create the simulator
79  VioManagerOptions params1;
80  params1.print_and_load(parser);
81  params1.print_and_load_simulation(parser);
82  Simulator sim1(params1);
83 
84  // Vector of stored measurements
85  std::vector<double> vec_imutime;
86  std::vector<double> vec_camtime;
87  std::vector<Eigen::Vector3d> vec_am;
88  std::vector<Eigen::Vector3d> vec_wm;
89  std::vector<std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>>> vec_feats;
90 
91  // Continue to simulate until we have processed all the measurements
92  while (sim1.ok()) {
93 
94  // IMU: get the next simulated IMU measurement if we have it
95  double time_imu;
96  Eigen::Vector3d wm, am;
97  bool hasimu = sim1.get_next_imu(time_imu, wm, am);
98  if (hasimu) {
99  vec_imutime.push_back(time_imu);
100  vec_am.push_back(am);
101  vec_wm.push_back(wm);
102  }
103 
104  // CAM: get the next simulated camera uv measurements if we have them
105  double time_cam;
106  std::vector<int> camids;
107  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> feats;
108  bool hascam = sim1.get_next_cam(time_cam, camids, feats);
109  if (hascam) {
110  vec_camtime.push_back(time_cam);
111  vec_feats.push_back(feats);
112  }
113  }
114 
115  //===================================================
116  //===================================================
117 
118  // Create the simulator
119  VioManagerOptions params2;
120  params2.print_and_load(parser);
121  params2.print_and_load_simulation(parser);
122  Simulator sim2(params2);
123  size_t ct_imu = 0;
124  size_t ct_cam = 0;
125 
126  // Continue to simulate until we have processed all the measurements
127  while (sim2.ok()) {
128 
129  // IMU: get the next simulated IMU measurement if we have it
130  double time_imu;
131  Eigen::Vector3d wm, am;
132  bool hasimu = sim2.get_next_imu(time_imu, wm, am);
133  if (hasimu) {
134  assert(time_imu == vec_imutime.at(ct_imu));
135  assert(wm(0) == vec_wm.at(ct_imu)(0));
136  assert(wm(1) == vec_wm.at(ct_imu)(1));
137  assert(wm(2) == vec_wm.at(ct_imu)(2));
138  assert(am(0) == vec_am.at(ct_imu)(0));
139  assert(am(1) == vec_am.at(ct_imu)(1));
140  assert(am(2) == vec_am.at(ct_imu)(2));
141  ct_imu++;
142  }
143 
144  // CAM: get the next simulated camera uv measurements if we have them
145  double time_cam;
146  std::vector<int> camids;
147  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> feats;
148  bool hascam = sim2.get_next_cam(time_cam, camids, feats);
149  if (hascam) {
150  assert(time_cam == vec_camtime.at(ct_cam));
151  for (size_t camid = 0; camid < feats.size(); camid++) {
152  for (size_t i = 0; i < feats.at(camid).size(); i++) {
153  assert(feats.at(camid).at(i).first == vec_feats.at(ct_cam).at(camid).at(i).first);
154  assert(feats.at(camid).at(i).second(0) == vec_feats.at(ct_cam).at(camid).at(i).second(0));
155  assert(feats.at(camid).at(i).second(1) == vec_feats.at(ct_cam).at(camid).at(i).second(1));
156  }
157  }
158  ct_cam++;
159  }
160  }
161 
162  // Done!
163  PRINT_INFO("success! they all are the same!\n");
164  return EXIT_SUCCESS;
165 }
main
int main(int argc, char **argv)
Definition: test_sim_repeat.cpp:46
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::VioManagerOptions::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: VioManagerOptions.h:62
ov_msckf::Simulator::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: Simulator.cpp:391
ov_core::Printer::setPrintLevel
static void setPrintLevel(const std::string &level)
VioManagerOptions.h
print.h
PRINT_INFO
#define PRINT_INFO(x...)
ov_msckf::VioManagerOptions::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: VioManagerOptions.h:545
ov_msckf::VioManagerOptions
Struct which stores all options needed for state estimation.
Definition: VioManagerOptions.h:56
Simulator.h
ov_msckf::Simulator::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: Simulator.cpp:311
signal_callback_handler
void signal_callback_handler(int signum)
Definition: test_sim_repeat.cpp:43
ov_msckf::Simulator
Master simulator class that generated visual-inertial measurements.
Definition: Simulator.h:52
ov_msckf::Simulator::ok
bool ok()
Returns if we are actively simulating.
Definition: Simulator.h:72


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