A single simulation run (the full state not just pose). More...
#include <ResultSimulation.h>
Public Member Functions | |
void | plot_cam_extrinsics (bool doplotting, double max_time=INFINITY) |
Will plot the camera calibration extrinsic transform. More... | |
void | plot_cam_instrinsics (bool doplotting, double max_time=INFINITY) |
Will plot the camera calibration intrinsics. More... | |
void | plot_imu_intrinsics (bool doplotting, double max_time=INFINITY) |
Will plot the imu intrinsic errors. More... | |
void | plot_state (bool doplotting, double max_time=INFINITY) |
Will plot the state error and its three sigma bounds. More... | |
void | plot_timeoff (bool doplotting, double max_time=INFINITY) |
Will plot the state imu camera offset and its sigma bound. More... | |
ResultSimulation (std::string path_est, std::string path_std, std::string path_gt) | |
Default constructor that will load our data from file. More... | |
Protected Attributes | |
std::vector< Eigen::VectorXd > | est_state |
std::vector< Eigen::VectorXd > | gt_state |
std::vector< Eigen::VectorXd > | state_cov |
A single simulation run (the full state not just pose).
This should match the recording logic that is in the ov_msckf::RosVisualizer in which we write both estimate, their deviation, and groundtruth to three files. We enforce that these files first contain the current IMU state, then time offset, number of cameras, then the camera calibration states. If we are not performing calibration these should all be written to file, just their deviation should be zero as they are 100% certain.
Definition at line 59 of file ResultSimulation.h.
ResultSimulation::ResultSimulation | ( | std::string | path_est, |
std::string | path_std, | ||
std::string | path_gt | ||
) |
Default constructor that will load our data from file.
path_est | Path to the estimate text file |
path_std | Path to the standard deviation file |
path_gt | Path to the groundtruth text file |
Assert they are of equal length
Definition at line 26 of file ResultSimulation.cpp.
void ResultSimulation::plot_cam_extrinsics | ( | bool | doplotting, |
double | max_time = INFINITY |
||
) |
Will plot the camera calibration extrinsic transform.
doplotting | True if you want to display the plots |
max_time | Max number of second we want to plot |
Definition at line 390 of file ResultSimulation.cpp.
void ResultSimulation::plot_cam_instrinsics | ( | bool | doplotting, |
double | max_time = INFINITY |
||
) |
Will plot the camera calibration intrinsics.
doplotting | True if you want to display the plots |
max_time | Max number of second we want to plot |
Definition at line 280 of file ResultSimulation.cpp.
void ResultSimulation::plot_imu_intrinsics | ( | bool | doplotting, |
double | max_time = INFINITY |
||
) |
Will plot the imu intrinsic errors.
doplotting | True if you want to display the plots |
max_time | Max number of second we want to plot |
Definition at line 502 of file ResultSimulation.cpp.
void ResultSimulation::plot_state | ( | bool | doplotting, |
double | max_time = INFINITY |
||
) |
Will plot the state error and its three sigma bounds.
doplotting | True if you want to display the plots |
max_time | Max number of second we want to plot |
Definition at line 42 of file ResultSimulation.cpp.
void ResultSimulation::plot_timeoff | ( | bool | doplotting, |
double | max_time = INFINITY |
||
) |
Will plot the state imu camera offset and its sigma bound.
doplotting | True if you want to display the plots |
max_time | Max number of second we want to plot |
Definition at line 204 of file ResultSimulation.cpp.
|
protected |
Definition at line 107 of file ResultSimulation.h.
|
protected |
Definition at line 107 of file ResultSimulation.h.
|
protected |
Definition at line 108 of file ResultSimulation.h.