Public Member Functions | Public Attributes
ssf_core::State Class Reference

#include <state.h>

List of all members.

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

Detailed Description

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.


Member Function Documentation

void ssf_core::State::getPoseCovariance ( geometry_msgs::PoseWithCovariance::_covariance_type &  cov)

writes the covariance corresponding to position and attitude to cov

Definition at line 59 of file state.cpp.

resets the state

3D vectors: 0; quaternion: unit quaternion; scale: 1; time:0; Error covariance: zeros

Definition at line 37 of file state.cpp.

void ssf_core::State::toExtStateMsg ( sensor_fusion_comm::ExtState &  state)

assembles an ExtState message from the state

it does not set the header

Definition at line 83 of file state.cpp.

void ssf_core::State::toPoseMsg ( geometry_msgs::PoseWithCovarianceStamped &  pose)

assembles a PoseWithCovarianceStamped message from the state

it does not set the header

Definition at line 76 of file state.cpp.

void ssf_core::State::toStateMsg ( sensor_fusion_comm::DoubleArrayStamped &  state)

assembles a DoubleArrayStamped message from the state

it does not set the header

Definition at line 90 of file state.cpp.


Member Data Documentation

Eigen::Matrix<double,3,1> ssf_core::State::a_m_

acceleration from IMU

Definition at line 70 of file state.h.

Eigen::Matrix<double, 3, 1> ssf_core::State::b_a_

acceleration biases (13-15 / 12-14)

Definition at line 60 of file state.h.

Eigen::Matrix<double, 3, 1> ssf_core::State::b_w_

gyro biases (10-12 / 9-11)

Definition at line 59 of file state.h.

visual scale (16 / 15)

Definition at line 63 of file state.h.

Eigen::Matrix<double, 3, 1> ssf_core::State::p_

position (IMU centered) (0-2 / 0-2)

Definition at line 56 of file state.h.

Eigen::Matrix<double, N_STATE, N_STATE> ssf_core::State::P_

error state covariance

Definition at line 74 of file state.h.

Eigen::Matrix<double, 3, 1> ssf_core::State::p_ci_

camera-imu position calibration (25-27 / 22-24)

Definition at line 66 of file state.h.

Eigen::Quaternion<double> ssf_core::State::q_

attitude (6- 9 / 6- 8)

Definition at line 58 of file state.h.

Eigen::Quaternion<double> ssf_core::State::q_ci_

camera-imu attitude calibration (21-24 / 19-21)

Definition at line 65 of file state.h.

Eigen::Quaternion<double> ssf_core::State::q_int_

this is the integrated ang. vel. no corrections applied, to use for delta rot in external algos...

Definition at line 72 of file state.h.

Eigen::Quaternion<double> ssf_core::State::q_wv_

vision-world attitude drift (17-20 / 16-18)

Definition at line 64 of file state.h.

time of this state estimate

Definition at line 76 of file state.h.

Eigen::Matrix<double, 3, 1> ssf_core::State::v_

velocity (3- 5 / 3- 5)

Definition at line 57 of file state.h.

Eigen::Matrix<double,3,1> ssf_core::State::w_m_

angular velocity from IMU

Definition at line 69 of file state.h.


The documentation for this class was generated from the following files:


ssf_core
Author(s): Stephan Weiss, Markus Achtelik
autogenerated on Mon Oct 6 2014 10:27:03