File ekf_vicon_imu_simple.hpp

Implements a testing class for the Vicon and IMU based estimator. It loads a yaml configuration file and a SL data file, estimate the state from these data and compare to the vicon trajectory.

License:

BSD 3-clause

Copyright

Copyright (c) 2020, New York University and Max Planck Gesellschaft

namespace mim_estimation
namespace test
class EstimatorViconImuTest

Public Functions

inline EstimatorViconImuTest(std::string yaml_file, std::string d_file)

This class tests the mim_estimation based on IMU and Vicon measurement.

inline void run()

run, simple method that execute the estimation of the base position from motion capture and IMU data saved from SL

inline void dump(std::string file_name)
inline void get_data_from_file(const int row, Eigen::Vector3d &gyroscope, Eigen::Vector3d &accelerometer, Eigen::Matrix4d &vicon_base_pose, Eigen::Quaterniond &input_vicon_base_quat, bool &vicon_is_new_frame)

get_data_from_file

Parameters:
  • row – row index homogenous to time/sampling_period.

  • gyroscope – output imu data copied from the data set

  • accelerometer – output imu data copied from the data set

  • unfiltered_joint_data – joint position copied from the data set

  • filtered_joint_data – filtered joint position copied from the data set

  • vicon_base_pose – position of the based measured form the Vicon system copied from the data set

  • vicon_is_new_frame – True is the Vicon data if actually a new one.

inline void subscribe_to_data_collector()

subscribe_to_data_collector, collect the address of all variables to save

inline void get_data_indexes()

get_data_indexes In order to parse the SL data file one need the indexes associated to the data.

This method computes the different names and indexes.

inline void display_one_statistics(double avg, double min, double max, std::string name)
inline void display_all_statistics()
inline void compute_all_statistics()
inline void compute_one_statistics(Eigen::Ref<Eigen::MatrixXd> mat, double &avg, double &min, double &max)

Public Members

double avg_err_base_pose
double avg_err_base_pose_x
double avg_err_base_pose_y
double avg_err_base_pose_z
double max_err_base_pose
double max_err_base_pose_x
double max_err_base_pose_y
double max_err_base_pose_z
double min_err_base_pose
double min_err_base_pose_x
double min_err_base_pose_y
double min_err_base_pose_z
double avg_err_base_quat_x
double avg_err_base_quat_y
double avg_err_base_quat_z
double max_err_base_quat_x
double max_err_base_quat_y
double max_err_base_quat_z
double min_err_base_quat_x
double min_err_base_quat_y
double min_err_base_quat_z

Private Members

YAML::Node config_
YAML::Node config_est_
double update_frequency_
io_tools::DataReader data_reader_
io_tools::NonRtDataCollector data_collector_
double time_
std::vector<int> gyroscope_ids_
std::vector<int> accelerometer_ids_
std::vector<int> vicon_base_pose_ids_
int vicon_is_new_frame_id_
Eigen::Vector3d input_gyroscope_
Eigen::Vector3d input_accelerometer_
Eigen::Matrix4d input_vicon_base_pose_
Eigen::Quaterniond input_vicon_base_quat_
bool input_vicon_is_new_frame_
Eigen::Vector3d output_imu_position_
Eigen::Quaterniond output_imu_orientation_
Eigen::Vector3d output_imu_linear_velocity_
Eigen::Vector3d output_imu_angular_velocty_
Eigen::Vector3d output_accel_bias_
Eigen::Vector3d output_gyro_bias_
Eigen::Vector3d output_base_position_
Eigen::Quaterniond output_base_orientation_
Eigen::Vector3d output_base_linear_velocity_
Eigen::Vector3d output_base_angular_velocity_
Eigen::MatrixXd error_base_pose_
Eigen::MatrixXd error_base_quat_
std::unique_ptr<mim_estimation::EkfViconImu> vicon_bse_