28 #if ROS_AVAILABLE == 1
31 #elif ROS_AVAILABLE == 2
33 #include <rclcpp/rclcpp.hpp>
38 std::shared_ptr<VioManager>
sys;
39 #if ROS_AVAILABLE == 1
40 std::shared_ptr<ROS1Visualizer>
viz;
41 #elif ROS_AVAILABLE == 2
42 std::shared_ptr<ROS2Visualizer>
viz;
46 int main(
int argc,
char **argv) {
49 std::string config_path =
"unset_path_to_config.yaml";
51 config_path = argv[1];
54 #if ROS_AVAILABLE == 1
56 ros::init(argc, argv,
"run_subscribe_msckf");
57 auto nh = std::make_shared<ros::NodeHandle>(
"~");
58 nh->param<std::string>(
"config_path", config_path, config_path);
59 #elif ROS_AVAILABLE == 2
61 rclcpp::init(argc, argv);
62 rclcpp::NodeOptions options;
63 options.allow_undeclared_parameters(
true);
64 options.automatically_declare_parameters_from_overrides(
true);
65 auto node = std::make_shared<rclcpp::Node>(
"run_subscribe_msckf", options);
66 node->get_parameter<std::string>(
"config_path", config_path);
70 auto parser = std::make_shared<ov_core::YamlParser>(config_path);
71 #if ROS_AVAILABLE == 1
72 parser->set_node_handler(nh);
73 #elif ROS_AVAILABLE == 2
74 parser->set_node(node);
78 std::string verbosity =
"DEBUG";
79 parser->parse_config(
"verbosity", verbosity);
86 sys = std::make_shared<VioManager>(params);
87 #if ROS_AVAILABLE == 1
88 viz = std::make_shared<ROS1Visualizer>(nh,
sys);
89 viz->setup_subscribers(parser);
90 #elif ROS_AVAILABLE == 2
91 viz = std::make_shared<ROS2Visualizer>(node,
sys);
92 viz->setup_subscribers(parser);
96 if (!parser->successful()) {
98 std::exit(EXIT_FAILURE);
103 #if ROS_AVAILABLE == 1
108 #elif ROS_AVAILABLE == 2
110 rclcpp::executors::MultiThreadedExecutor executor;
111 executor.add_node(node);
116 viz->visualize_final();
117 #if ROS_AVAILABLE == 1
119 #elif ROS_AVAILABLE == 2