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;
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;
96 PRINT_DEBUG(
"new cam measurement = %0.15g | %u cameras | uvs(0) = %u \n", time_cam, camids.size(), feats.at(0).size());
Extended Kalman Filter estimator.
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.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool get_next_imu(double &time_imu, Eigen::Vector3d &wm, Eigen::Vector3d &am)
Gets the next inertial reading if we have one.
std::shared_ptr< Simulator > sim
bool ok()
Returns if we are actively simulating.
Struct which stores all options needed for state estimation.
void signal_callback_handler(int signum)
static void setPrintLevel(const std::string &level)
int main(int argc, char **argv)
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...
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.
Master simulator class that generated visual-inertial measurements.
#define PRINT_DEBUG(x...)