#include <imu_measurement.h>
Public Member Functions | |
ImuMeasurement () | |
ImuMeasurement (const ImuMeasurement &other) | |
void | setAccBiasCovariance (double v_x, double v_y, double v_z) |
Set noise levels for the accelerometer bias covariance. | |
void | setAngularRateCovariance (double v) |
Set covariance diagonal of the angular rate measure. | |
void | setGyroBiasCovariance (double v_x, double v_y, double v_z) |
Set noise levels for the gyro bias covariance. | |
void | setLinearAccelerationCovariance (double v) |
Set covariance diagonal of the acceleration measure. | |
Public Attributes | |
Eigen::Matrix3d | accBiasCovariance |
Eigen::Vector3d | accBiasPerturbation |
Eigen::Vector3d | angularRate |
Eigen::Matrix3d | angularRateCovariance |
Eigen::Vector3d | angularRatePerturbation |
Eigen::Matrix3d | gyroBiasCovariance |
Eigen::Vector3d | gyroBiasPerturbation |
Eigen::Vector3d | linearAcceleration |
Eigen::Matrix3d | linearAccelerationCovariance |
Eigen::Vector3d | linearAccelerationPerturbation |
The class basically represents measurements obtained from an IMU
Definition at line 50 of file imu_measurement.h.
imu_filter::ImuMeasurement::ImuMeasurement | ( | ) | [inline] |
Definition at line 53 of file imu_measurement.h.
imu_filter::ImuMeasurement::ImuMeasurement | ( | const ImuMeasurement & | other | ) | [inline] |
Definition at line 67 of file imu_measurement.h.
void imu_filter::ImuMeasurement::setAccBiasCovariance | ( | double | v_x, |
double | v_y, | ||
double | v_z | ||
) | [inline] |
Set noise levels for the accelerometer bias covariance.
Definition at line 114 of file imu_measurement.h.
void imu_filter::ImuMeasurement::setAngularRateCovariance | ( | double | v | ) | [inline] |
Set covariance diagonal of the angular rate measure.
Definition at line 84 of file imu_measurement.h.
void imu_filter::ImuMeasurement::setGyroBiasCovariance | ( | double | v_x, |
double | v_y, | ||
double | v_z | ||
) | [inline] |
Set noise levels for the gyro bias covariance.
Definition at line 104 of file imu_measurement.h.
void imu_filter::ImuMeasurement::setLinearAccelerationCovariance | ( | double | v | ) | [inline] |
Set covariance diagonal of the acceleration measure.
Definition at line 94 of file imu_measurement.h.
Eigen::Matrix3d imu_filter::ImuMeasurement::accBiasCovariance |
accelerometer bias covariance
Definition at line 133 of file imu_measurement.h.
Eigen::Vector3d imu_filter::ImuMeasurement::accBiasPerturbation |
perturbation level for the acclerometer bias
Definition at line 128 of file imu_measurement.h.
Eigen::Vector3d imu_filter::ImuMeasurement::angularRate |
angular Rate measurement
Definition at line 121 of file imu_measurement.h.
Eigen::Matrix3d imu_filter::ImuMeasurement::angularRateCovariance |
angular rate covariance
Definition at line 130 of file imu_measurement.h.
Eigen::Vector3d imu_filter::ImuMeasurement::angularRatePerturbation |
perturbation level for the angular rate
Definition at line 125 of file imu_measurement.h.
Eigen::Matrix3d imu_filter::ImuMeasurement::gyroBiasCovariance |
gyro bias covariance
Definition at line 132 of file imu_measurement.h.
Eigen::Vector3d imu_filter::ImuMeasurement::gyroBiasPerturbation |
perturbation level for the gyro bias
Definition at line 127 of file imu_measurement.h.
Eigen::Vector3d imu_filter::ImuMeasurement::linearAcceleration |
linear acceleration measurement
Definition at line 123 of file imu_measurement.h.
Eigen::Matrix3d imu_filter::ImuMeasurement::linearAccelerationCovariance |
linear acceleration Covariance
Definition at line 131 of file imu_measurement.h.
Eigen::Vector3d imu_filter::ImuMeasurement::linearAccelerationPerturbation |
perturbation level for the linear acceleration
Definition at line 126 of file imu_measurement.h.