test_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 <cmath>
23 #include <csignal>
24 #include <deque>
25 #include <iomanip>
26 #include <sstream>
27 #include <unistd.h>
28 #include <vector>
29 
30 #include <boost/date_time/posix_time/posix_time.hpp>
31 #include <boost/filesystem.hpp>
32 
33 #if ROS_AVAILABLE == 1
34 #include <ros/ros.h>
35 #endif
36 
38 #include "sim/SimulatorInit.h"
39 
40 using namespace ov_init;
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  // 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, "test_sim_meas");
57  auto nh = std::make_shared<ros::NodeHandle>("~");
58  nh->param<std::string>("config_path", config_path, config_path);
59 #endif
60 
61  // Load the config
62  auto parser = std::make_shared<ov_core::YamlParser>(config_path);
63 #if ROS_AVAILABLE == 1
64  parser->set_node_handler(nh);
65 #endif
66 
67  // Verbosity
68  std::string verbosity = "INFO";
69  parser->parse_config("verbosity", verbosity);
71 
72  // Create the simulator
74  params.print_and_load(parser);
75  params.print_and_load_simulation(parser);
76  SimulatorInit sim(params);
77 
78  // Continue to simulate until we have processed all the measurements
79  signal(SIGINT, signal_callback_handler);
80  while (sim.ok()) {
81 
82  // IMU: get the next simulated IMU measurement if we have it
83  double time_imu;
84  Eigen::Vector3d wm, am;
85  bool hasimu = sim.get_next_imu(time_imu, wm, am);
86  if (hasimu) {
87  PRINT_DEBUG("new imu measurement = %0.15g | w = %0.3g | a = %0.3g\n", time_imu, wm.norm(), am.norm());
88  }
89 
90  // CAM: get the next simulated camera uv measurements if we have them
91  double time_cam;
92  std::vector<int> camids;
93  std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> feats;
94  bool hascam = sim.get_next_cam(time_cam, camids, feats);
95  if (hascam) {
96  PRINT_DEBUG("new cam measurement = %0.15g | %u cameras | uvs(0) = %u \n", time_cam, camids.size(), feats.at(0).size());
97  }
98  }
99 
100  // Done!
101  return EXIT_SUCCESS;
102 };
ov_init::InertialInitializerOptions
Struct which stores all options needed for state estimation.
Definition: InertialInitializerOptions.h:49
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
SimulatorInit.h
ov_init::InertialInitializerOptions::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: InertialInitializerOptions.h:388
ros.h
PRINT_DEBUG
#define PRINT_DEBUG(x...)
ov_init::SimulatorInit::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: SimulatorInit.cpp:289
ov_init::SimulatorInit::ok
bool ok()
Returns if we are actively simulating.
Definition: SimulatorInit.h:71
ov_core::Printer::setPrintLevel
static void setPrintLevel(const std::string &level)
ov_init::InertialInitializerOptions::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: InertialInitializerOptions.h:55
ov_init::SimulatorInit::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: SimulatorInit.cpp:350
main
int main(int argc, char **argv)
Definition: test_simulation.cpp:46
ov_init
State initialization code.
Definition: Factor_GenericPrior.h:27
signal_callback_handler
void signal_callback_handler(int signum)
Definition: test_simulation.cpp:43
ov_init::SimulatorInit
Master simulator class that generated visual-inertial measurements.
Definition: SimulatorInit.h:52
InertialInitializerOptions.h


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