30 #include <boost/date_time/posix_time/posix_time.hpp>
31 #include <boost/filesystem.hpp>
33 #if ROS_AVAILABLE == 1
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
57 auto nh = std::make_shared<ros::NodeHandle>(
"~");
58 nh->param<std::string>(
"config_path", config_path, config_path);
62 auto parser = std::make_shared<ov_core::YamlParser>(config_path);
63 #if ROS_AVAILABLE == 1
64 parser->set_node_handler(nh);
68 std::string verbosity =
"INFO";
69 parser->parse_config(
"verbosity", verbosity);
84 Eigen::Vector3d wm, am;
85 bool hasimu =
sim.get_next_imu(time_imu, wm, am);
87 PRINT_DEBUG(
"new imu measurement = %0.15g | w = %0.3g | a = %0.3g\n", time_imu, wm.norm(), am.norm());
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);
96 PRINT_DEBUG(
"new cam measurement = %0.15g | %u cameras | uvs(0) = %u \n", time_cam, camids.size(), feats.at(0).size());