32 #if ROS_AVAILABLE == 1
35 #elif ROS_AVAILABLE == 2
37 #include <rclcpp/rclcpp.hpp>
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;
54 int main(
int argc,
char **argv) {
57 std::string config_path =
"unset_path_to_config.yaml";
59 config_path = argv[1];
62 #if ROS_AVAILABLE == 1
65 auto nh = std::make_shared<ros::NodeHandle>(
"~");
66 nh->param<std::string>(
"config_path", config_path, config_path);
67 #elif ROS_AVAILABLE == 2
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);
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);
86 std::string verbosity =
"INFO";
87 parser->parse_config(
"verbosity", verbosity);
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);
106 if (!parser->successful()) {
108 std::exit(EXIT_FAILURE);
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);
123 std::exit(EXIT_FAILURE);
128 imustate(0, 0) -=
sim->get_true_parameters().calib_camimu_dt;
131 sys->initialize_with_gt(imustate);
138 double buffer_timecam = -1;
139 std::vector<int> buffer_camids;
140 std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> buffer_feats;
143 #if ROS_AVAILABLE == 1
145 #elif ROS_AVAILABLE == 2
146 while (
sim->ok() && rclcpp::ok()) {
154 bool hasimu =
sim->get_next_imu(message_imu.
timestamp, message_imu.
wm, message_imu.
am);
156 sys->feed_measurement_imu(message_imu);
157 #if ROS_AVAILABLE == 1 || ROS_AVAILABLE == 2
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);
168 if (buffer_timecam != -1) {
169 sys->feed_measurement_simulation(buffer_timecam, buffer_camids, buffer_feats);
170 #if ROS_AVAILABLE == 1 || ROS_AVAILABLE == 2
174 buffer_timecam = time_cam;
175 buffer_camids = camids;
176 buffer_feats = feats;
181 #if ROS_AVAILABLE == 1
182 viz->visualize_final();
184 #elif ROS_AVAILABLE == 2
185 viz->visualize_final();