run_simulation.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 <csignal>
23 #include <memory>
24 
25 #include "core/VioManager.h"
26 #include "sim/Simulator.h"
27 #include "utils/colors.h"
28 #include "utils/dataset_reader.h"
29 #include "utils/print.h"
30 #include "utils/sensor_data.h"
31 
32 #if ROS_AVAILABLE == 1
33 #include "ros/ROS1Visualizer.h"
34 #include <ros/ros.h>
35 #elif ROS_AVAILABLE == 2
36 #include "ros/ROS2Visualizer.h"
37 #include <rclcpp/rclcpp.hpp>
38 #endif
39 
40 using namespace ov_msckf;
41 
42 std::shared_ptr<Simulator> sim;
43 std::shared_ptr<VioManager> sys;
44 #if ROS_AVAILABLE == 1
45 std::shared_ptr<ROS1Visualizer> viz;
46 #elif ROS_AVAILABLE == 2
47 std::shared_ptr<ROS2Visualizer> viz;
48 #endif
49 
50 // Define the function to be called when ctrl-c (SIGINT) is sent to process
51 void signal_callback_handler(int signum) { std::exit(signum); }
52 
53 // Main function
54 int main(int argc, char **argv) {
55 
56  // Ensure we have a path, if the user passes it then we should use it
57  std::string config_path = "unset_path_to_config.yaml";
58  if (argc > 1) {
59  config_path = argv[1];
60  }
61 
62 #if ROS_AVAILABLE == 1
63  // Launch our ros node
64  ros::init(argc, argv, "run_simulation");
65  auto nh = std::make_shared<ros::NodeHandle>("~");
66  nh->param<std::string>("config_path", config_path, config_path);
67 #elif ROS_AVAILABLE == 2
68  // Launch our ros node
69  rclcpp::init(argc, argv);
70  rclcpp::NodeOptions options;
71  options.allow_undeclared_parameters(true);
72  options.automatically_declare_parameters_from_overrides(true);
73  auto node = std::make_shared<rclcpp::Node>("run_simulation", options);
74  node->get_parameter<std::string>("config_path", config_path);
75 #endif
76 
77  // Load the config
78  auto parser = std::make_shared<ov_core::YamlParser>(config_path);
79 #if ROS_AVAILABLE == 1
80  parser->set_node_handler(nh);
81 #elif ROS_AVAILABLE == 2
82  parser->set_node(node);
83 #endif
84 
85  // Verbosity
86  std::string verbosity = "INFO";
87  parser->parse_config("verbosity", verbosity);
89 
90  // Create our VIO system
91  VioManagerOptions params;
92  params.print_and_load(parser);
93  params.print_and_load_simulation(parser);
94  params.num_opencv_threads = 0; // for repeatability
95  params.use_multi_threading_pubs = false;
96  params.use_multi_threading_subs = false;
97  sim = std::make_shared<Simulator>(params);
98  sys = std::make_shared<VioManager>(params);
99 #if ROS_AVAILABLE == 1
100  viz = std::make_shared<ROS1Visualizer>(nh, sys, sim);
101 #elif ROS_AVAILABLE == 2
102  viz = std::make_shared<ROS2Visualizer>(node, sys, sim);
103 #endif
104 
105  // Ensure we read in all parameters required
106  if (!parser->successful()) {
107  PRINT_ERROR(RED "unable to parse all parameters, please fix\n" RESET);
108  std::exit(EXIT_FAILURE);
109  }
110 
111  //===================================================================================
112  //===================================================================================
113  //===================================================================================
114 
115  // Get initial state
116  // NOTE: we are getting it at the *next* timestep so we get the first IMU message
117  double next_imu_time = sim->current_timestamp() + 1.0 / params.sim_freq_imu;
118  Eigen::Matrix<double, 17, 1> imustate;
119  bool success = sim->get_state(next_imu_time, imustate);
120  if (!success) {
121  PRINT_ERROR(RED "[SIM]: Could not initialize the filter to the first state\n" RESET);
122  PRINT_ERROR(RED "[SIM]: Did the simulator load properly???\n" RESET);
123  std::exit(EXIT_FAILURE);
124  }
125 
126  // Since the state time is in the camera frame of reference
127  // Subtract out the imu to camera time offset
128  imustate(0, 0) -= sim->get_true_parameters().calib_camimu_dt;
129 
130  // Initialize our filter with the groundtruth
131  sys->initialize_with_gt(imustate);
132 
133  //===================================================================================
134  //===================================================================================
135  //===================================================================================
136 
137  // Buffer our camera image
138  double buffer_timecam = -1;
139  std::vector<int> buffer_camids;
140  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> buffer_feats;
141 
142  // Step through the rosbag
143 #if ROS_AVAILABLE == 1
144  while (sim->ok() && ros::ok()) {
145 #elif ROS_AVAILABLE == 2
146  while (sim->ok() && rclcpp::ok()) {
147 #else
148  signal(SIGINT, signal_callback_handler);
149  while (sim->ok()) {
150 #endif
151 
152  // IMU: get the next simulated IMU measurement if we have it
153  ov_core::ImuData message_imu;
154  bool hasimu = sim->get_next_imu(message_imu.timestamp, message_imu.wm, message_imu.am);
155  if (hasimu) {
156  sys->feed_measurement_imu(message_imu);
157 #if ROS_AVAILABLE == 1 || ROS_AVAILABLE == 2
158  viz->visualize_odometry(message_imu.timestamp);
159 #endif
160  }
161 
162  // CAM: get the next simulated camera uv measurements if we have them
163  double time_cam;
164  std::vector<int> camids;
165  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> feats;
166  bool hascam = sim->get_next_cam(time_cam, camids, feats);
167  if (hascam) {
168  if (buffer_timecam != -1) {
169  sys->feed_measurement_simulation(buffer_timecam, buffer_camids, buffer_feats);
170 #if ROS_AVAILABLE == 1 || ROS_AVAILABLE == 2
171  viz->visualize();
172 #endif
173  }
174  buffer_timecam = time_cam;
175  buffer_camids = camids;
176  buffer_feats = feats;
177  }
178  }
179 
180  // Final visualization
181 #if ROS_AVAILABLE == 1
182  viz->visualize_final();
183  ros::shutdown();
184 #elif ROS_AVAILABLE == 2
185  viz->visualize_final();
186  rclcpp::shutdown();
187 #endif
188 
189  // Done!
190  return EXIT_SUCCESS;
191 }
ROS1Visualizer.h
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
sensor_data.h
signal_callback_handler
void signal_callback_handler(int signum)
Definition: run_simulation.cpp:51
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
ros::shutdown
ROSCPP_DECL void shutdown()
PRINT_ERROR
#define PRINT_ERROR(x...)
ov_msckf::VioManagerOptions::use_multi_threading_pubs
bool use_multi_threading_pubs
If our ROS image publisher should be async (if sim this should be no!)
Definition: VioManagerOptions.h:415
ros::ok
ROSCPP_DECL bool ok()
main
int main(int argc, char **argv)
Definition: run_simulation.cpp:54
viz
std::shared_ptr< ROS1Visualizer > viz
Definition: ros1_serial_msckf.cpp:38
ROS2Visualizer.h
sys
std::shared_ptr< VioManager > sys
Definition: run_simulation.cpp:43
ov_core::Printer::setPrintLevel
static void setPrintLevel(const std::string &level)
VioManager.h
ov_core::ImuData::wm
Eigen::Matrix< double, 3, 1 > wm
ov_core::ImuData
ov_msckf::VioManagerOptions::num_opencv_threads
int num_opencv_threads
Threads our front-end should try to use (opencv uses this also)
Definition: VioManagerOptions.h:412
ov_msckf::VioManagerOptions::use_multi_threading_subs
bool use_multi_threading_subs
If our ROS subscriber callbacks should be async (if sim and serial then this should be no!...
Definition: VioManagerOptions.h:418
ov_core::ImuData::am
Eigen::Matrix< double, 3, 1 > am
print.h
colors.h
RESET
#define RESET
dataset_reader.h
sim
std::shared_ptr< Simulator > sim
Definition: run_simulation.cpp:42
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
ov_core::ImuData::timestamp
double timestamp
Simulator.h
ov_msckf::VioManagerOptions::sim_freq_imu
double sim_freq_imu
Frequency (Hz) that we will simulate our inertial measurement unit.
Definition: VioManagerOptions.h:531
RED
RED


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