run_subscribe_msckf.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 <memory>
23 
24 #include "core/VioManager.h"
25 #include "core/VioManagerOptions.h"
26 #include "utils/dataset_reader.h"
27 
28 #if ROS_AVAILABLE == 1
29 #include "ros/ROS1Visualizer.h"
30 #include <ros/ros.h>
31 #elif ROS_AVAILABLE == 2
32 #include "ros/ROS2Visualizer.h"
33 #include <rclcpp/rclcpp.hpp>
34 #endif
35 
36 using namespace ov_msckf;
37 
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;
43 #endif
44 
45 // Main function
46 int main(int argc, char **argv) {
47 
48  // Ensure we have a path, if the user passes it then we should use it
49  std::string config_path = "unset_path_to_config.yaml";
50  if (argc > 1) {
51  config_path = argv[1];
52  }
53 
54 #if ROS_AVAILABLE == 1
55  // Launch our ros node
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
60  // Launch our ros node
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);
67 #endif
68 
69  // Load the config
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);
75 #endif
76 
77  // Verbosity
78  std::string verbosity = "DEBUG";
79  parser->parse_config("verbosity", verbosity);
81 
82  // Create our VIO system
83  VioManagerOptions params;
84  params.print_and_load(parser);
85  params.use_multi_threading_subs = true;
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);
93 #endif
94 
95  // Ensure we read in all parameters required
96  if (!parser->successful()) {
97  PRINT_ERROR(RED "unable to parse all parameters, please fix\n" RESET);
98  std::exit(EXIT_FAILURE);
99  }
100 
101  // Spin off to ROS
102  PRINT_DEBUG("done...spinning to ros\n");
103 #if ROS_AVAILABLE == 1
104  // ros::spin();
106  spinner.start();
108 #elif ROS_AVAILABLE == 2
109  // rclcpp::spin(node);
110  rclcpp::executors::MultiThreadedExecutor executor;
111  executor.add_node(node);
112  executor.spin();
113 #endif
114 
115  // Final visualization
116  viz->visualize_final();
117 #if ROS_AVAILABLE == 1
118  ros::shutdown();
119 #elif ROS_AVAILABLE == 2
120  rclcpp::shutdown();
121 #endif
122 
123  // Done!
124  return EXIT_SUCCESS;
125 }
ROS1Visualizer.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
sys
std::shared_ptr< VioManager > sys
Definition: run_subscribe_msckf.cpp:38
ros.h
PRINT_DEBUG
#define PRINT_DEBUG(x...)
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ros::AsyncSpinner
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...)
main
int main(int argc, char **argv)
Definition: run_subscribe_msckf.cpp:46
spinner
void spinner()
viz
std::shared_ptr< ROS1Visualizer > viz
Definition: ros1_serial_msckf.cpp:38
ROS2Visualizer.h
ov_core::Printer::setPrintLevel
static void setPrintLevel(const std::string &level)
VioManager.h
VioManagerOptions.h
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
ros::waitForShutdown
ROSCPP_DECL void waitForShutdown()
RESET
#define RESET
dataset_reader.h
ov_msckf::VioManagerOptions
Struct which stores all options needed for state estimation.
Definition: VioManagerOptions.h:56
RED
RED


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