Public Member Functions |
void | getPoseCovariance (geometry_msgs::PoseWithCovariance::_covariance_type &cov) |
| writes the covariance corresponding to position and attitude to cov
|
void | reset () |
| resets the state
|
void | toExtStateMsg (sensor_fusion_comm::ExtState &state) |
| assembles an ExtState message from the state
|
void | toPoseMsg (geometry_msgs::PoseWithCovarianceStamped &pose) |
| assembles a PoseWithCovarianceStamped message from the state
|
void | toStateMsg (sensor_fusion_comm::DoubleArrayStamped &state) |
| assembles a DoubleArrayStamped message from the state
|
Public Attributes |
Eigen::Matrix< double, 3, 1 > | a_m_ |
| acceleration from IMU
|
Eigen::Matrix< double, 3, 1 > | b_a_ |
| acceleration biases (13-15 / 12-14)
|
Eigen::Matrix< double, 3, 1 > | b_w_ |
| gyro biases (10-12 / 9-11)
|
double | L_ |
| visual scale (16 / 15)
|
Eigen::Matrix< double, 3, 1 > | p_ |
| position (IMU centered) (0-2 / 0-2)
|
Eigen::Matrix< double, N_STATE,
N_STATE > | P_ |
| error state covariance
|
Eigen::Matrix< double, 3, 1 > | p_ci_ |
| camera-imu position calibration (25-27 / 22-24)
|
Eigen::Quaternion< double > | q_ |
| attitude (6- 9 / 6- 8)
|
Eigen::Quaternion< double > | q_ci_ |
| camera-imu attitude calibration (21-24 / 19-21)
|
Eigen::Quaternion< double > | q_int_ |
| this is the integrated ang. vel. no corrections applied, to use for delta rot in external algos...
|
Eigen::Quaternion< double > | q_wv_ |
| vision-world attitude drift (17-20 / 16-18)
|
double | time_ |
| time of this state estimate
|
Eigen::Matrix< double, 3, 1 > | v_ |
| velocity (3- 5 / 3- 5)
|
Eigen::Matrix< double, 3, 1 > | w_m_ |
| angular velocity from IMU
|
This class defines the state, its associated error state covarinace and the system inputs. The values in the braces determine the state's position in the state vector / error state vector.
Definition at line 52 of file state.h.