Public Types | Public Member Functions | Static Public Attributes | Private Attributes
imu_filter::ImuState Class Reference

#include <imu_state.h>

List of all members.

Public Types

typedef Eigen::Matrix< double,
Dimension, Dimension
CovarianceMatrix
typedef Eigen::Matrix< double,
Dimension, 1 > 
StateVector

Public Member Functions

const Eigen::Vector3d & accBias () const
 getter for the accBias
Eigen::Vector3d & accBias ()
 getter for the accBias
const Eigen::Quaterniond & body2ImuRotation () const
 getter for the rotation from target frame to imu frame
const Eigen::Vector3d & body2ImuTranslation () const
 getter for the translation from target frame to imu frame
const CovarianceMatrixcovariance () const
 getter for the covariance matrix
CovarianceMatrixcovariance ()
 getter for the covariance matrix
void fixCovariance ()
 Fix those parts of covaraince matrix that are not estimated at the moment.
const Eigen::Vector3d & gravity () const
 getter for the gravity
Eigen::Vector3d & gravity ()
 getter for the gravity
const Eigen::Vector3d & gyroBias () const
 getter for the gyroBias
Eigen::Vector3d & gyroBias ()
 getter for the gyroBias
 ImuState ()
 ImuState (const ImuState &other)
ImuStateoperator= (const ImuState &other)
const Eigen::Quaterniond & orientation () const
 getter for the orientation
Eigen::Quaterniond & orientation ()
 getter for the orientation
const Eigen::Vector3d & position () const
 getter for the position
Eigen::Vector3d & position ()
 getter for the position
void setAccBias (const Eigen::Vector3d &newAccBias)
 setter for the accBias
void setAccBiasRange (double rx, double ry, double rz)
 set permitted maximum range for the accelerometer bias
void setBody2ImuRotation (const Eigen::Quaterniond &rot)
 setter for the rotation from target frame to imu frame
void setBody2ImuTranslation (const Eigen::Vector3d &trans)
 setter for the translation from target frame to imu frame
void setEstimateAccBias (bool v)
 set whether accelerometer bias is part of the estimated state variables or not!
void setEstimateGravity (bool v)
 set whether gravity is part of the estimated state variables or not!
void setEstimateGyroBias (bool v)
 set whether gyro bias is part of the estimated state variables or not!
void setGravity (const Eigen::Vector3d &newGravity)
 setter for the gravity
void setGyroBias (const Eigen::Vector3d &newGyroBias)
 setter for the gyroBias
void setGyroBiasRange (double rx, double ry, double rz)
 set permitted maximum range for the gyro bias
void setOrientation (const Eigen::Quaterniond &newOrientation)
 setter for the orientation
void setParameter (const StateVector &vector)
 set the parameters of the state
void setPosition (const Eigen::Vector3d &newPosition)
 setter for the position
void setVelocity (const Eigen::Vector3d &newVelocity)
 setter for the velocity
void toVector (StateVector &vec) const
 retrieve vector representation of the state This will give back a "vector" view of the state, for usage in the filtering equations
void update (const StateVector &updateVector)
 update the state vector (additive update)
const Eigen::Vector3d & velocity () const
 getter for the velocity
Eigen::Vector3d & velocity ()
 getter for the velocity
const Eigen::Affine3d & world2Imu ()
 Get the current pose estimate of the IMU state as transformation matrix.

Static Public Attributes

static const size_t Dimension = 19

Private Attributes

Eigen::Vector3d accBias_
Eigen::Vector3d accBiasRange_
Eigen::Quaterniond body2ImuR_
Eigen::Vector3d body2ImuT_
CovarianceMatrix covariance_
bool estimate_acc_bias_
bool estimate_gravity_
bool estimate_gyro_bias_
Eigen::Vector3d gravity_
Eigen::Vector3d gyroBias_
Eigen::Vector3d gyroBiasRange_
Eigen::Quaterniond orientation_
Eigen::Vector3d position_
Eigen::Vector3d velocity_
Eigen::Affine3d world2ImuPose_

Detailed Description

The class is responsible for storing all information about the Kalman state

Definition at line 58 of file imu_state.h.


Member Typedef Documentation

Typedef for the covariance Matrix

Definition at line 63 of file imu_state.h.

typedef Eigen::Matrix<double, Dimension, 1> imu_filter::ImuState::StateVector

Typedef for the state vector

Definition at line 62 of file imu_state.h.


Constructor & Destructor Documentation

Definition at line 65 of file imu_state.h.

imu_filter::ImuState::ImuState ( const ImuState other) [inline]

Definition at line 84 of file imu_state.h.


Member Function Documentation

const Eigen::Vector3d& imu_filter::ImuState::accBias ( ) const [inline]

getter for the accBias

Definition at line 243 of file imu_state.h.

Eigen::Vector3d& imu_filter::ImuState::accBias ( ) [inline]

getter for the accBias

Definition at line 248 of file imu_state.h.

const Eigen::Quaterniond& imu_filter::ImuState::body2ImuRotation ( ) const [inline]

getter for the rotation from target frame to imu frame

Definition at line 283 of file imu_state.h.

const Eigen::Vector3d& imu_filter::ImuState::body2ImuTranslation ( ) const [inline]

getter for the translation from target frame to imu frame

Definition at line 293 of file imu_state.h.

getter for the covariance matrix

Definition at line 273 of file imu_state.h.

getter for the covariance matrix

Definition at line 278 of file imu_state.h.

Fix those parts of covaraince matrix that are not estimated at the moment.

Definition at line 374 of file imu_state.h.

const Eigen::Vector3d& imu_filter::ImuState::gravity ( ) const [inline]

getter for the gravity

Definition at line 258 of file imu_state.h.

Eigen::Vector3d& imu_filter::ImuState::gravity ( ) [inline]

getter for the gravity

Definition at line 263 of file imu_state.h.

const Eigen::Vector3d& imu_filter::ImuState::gyroBias ( ) const [inline]

getter for the gyroBias

Definition at line 228 of file imu_state.h.

Eigen::Vector3d& imu_filter::ImuState::gyroBias ( ) [inline]

getter for the gyroBias

Definition at line 233 of file imu_state.h.

ImuState& imu_filter::ImuState::operator= ( const ImuState other) [inline]

Definition at line 99 of file imu_state.h.

const Eigen::Quaterniond& imu_filter::ImuState::orientation ( ) const [inline]

getter for the orientation

Definition at line 180 of file imu_state.h.

Eigen::Quaterniond& imu_filter::ImuState::orientation ( ) [inline]

getter for the orientation

Definition at line 185 of file imu_state.h.

const Eigen::Vector3d& imu_filter::ImuState::position ( ) const [inline]

getter for the position

Definition at line 198 of file imu_state.h.

Eigen::Vector3d& imu_filter::ImuState::position ( ) [inline]

getter for the position

Definition at line 203 of file imu_state.h.

void imu_filter::ImuState::setAccBias ( const Eigen::Vector3d &  newAccBias) [inline]

setter for the accBias

Definition at line 253 of file imu_state.h.

void imu_filter::ImuState::setAccBiasRange ( double  rx,
double  ry,
double  rz 
) [inline]

set permitted maximum range for the accelerometer bias

values with absolute value higher than this will get clamped!

Definition at line 332 of file imu_state.h.

void imu_filter::ImuState::setBody2ImuRotation ( const Eigen::Quaterniond &  rot) [inline]

setter for the rotation from target frame to imu frame

Definition at line 288 of file imu_state.h.

void imu_filter::ImuState::setBody2ImuTranslation ( const Eigen::Vector3d &  trans) [inline]

setter for the translation from target frame to imu frame

Definition at line 298 of file imu_state.h.

void imu_filter::ImuState::setEstimateAccBias ( bool  v) [inline]

set whether accelerometer bias is part of the estimated state variables or not!

Definition at line 313 of file imu_state.h.

void imu_filter::ImuState::setEstimateGravity ( bool  v) [inline]

set whether gravity is part of the estimated state variables or not!

Definition at line 303 of file imu_state.h.

void imu_filter::ImuState::setEstimateGyroBias ( bool  v) [inline]

set whether gyro bias is part of the estimated state variables or not!

Definition at line 308 of file imu_state.h.

void imu_filter::ImuState::setGravity ( const Eigen::Vector3d &  newGravity) [inline]

setter for the gravity

Definition at line 268 of file imu_state.h.

void imu_filter::ImuState::setGyroBias ( const Eigen::Vector3d &  newGyroBias) [inline]

setter for the gyroBias

Definition at line 238 of file imu_state.h.

void imu_filter::ImuState::setGyroBiasRange ( double  rx,
double  ry,
double  rz 
) [inline]

set permitted maximum range for the gyro bias

values with absolute value higher than this will get clamped!

Definition at line 320 of file imu_state.h.

void imu_filter::ImuState::setOrientation ( const Eigen::Quaterniond &  newOrientation) [inline]

setter for the orientation

Definition at line 190 of file imu_state.h.

void imu_filter::ImuState::setParameter ( const StateVector vector) [inline]

set the parameters of the state

Parameters:
vectorstate parameters to set

Definition at line 154 of file imu_state.h.

void imu_filter::ImuState::setPosition ( const Eigen::Vector3d &  newPosition) [inline]

setter for the position

Definition at line 208 of file imu_state.h.

void imu_filter::ImuState::setVelocity ( const Eigen::Vector3d &  newVelocity) [inline]

setter for the velocity

Definition at line 223 of file imu_state.h.

void imu_filter::ImuState::toVector ( StateVector vec) const [inline]

retrieve vector representation of the state This will give back a "vector" view of the state, for usage in the filtering equations

Definition at line 343 of file imu_state.h.

void imu_filter::ImuState::update ( const StateVector updateVector) [inline]

update the state vector (additive update)

Parameters:
updateVectorcomputed update vector from the Kalman filter

Definition at line 119 of file imu_state.h.

const Eigen::Vector3d& imu_filter::ImuState::velocity ( ) const [inline]

getter for the velocity

Definition at line 213 of file imu_state.h.

Eigen::Vector3d& imu_filter::ImuState::velocity ( ) [inline]

getter for the velocity

Definition at line 218 of file imu_state.h.

const Eigen::Affine3d& imu_filter::ImuState::world2Imu ( ) [inline]

Get the current pose estimate of the IMU state as transformation matrix.

Definition at line 395 of file imu_state.h.


Member Data Documentation

Eigen::Vector3d imu_filter::ImuState::accBias_ [private]

Definition at line 416 of file imu_state.h.

Eigen::Vector3d imu_filter::ImuState::accBiasRange_ [private]

Definition at line 426 of file imu_state.h.

Eigen::Quaterniond imu_filter::ImuState::body2ImuR_ [private]

Definition at line 429 of file imu_state.h.

Eigen::Vector3d imu_filter::ImuState::body2ImuT_ [private]

Definition at line 430 of file imu_state.h.

Definition at line 422 of file imu_state.h.

const size_t imu_filter::ImuState::Dimension = 19 [static]

Dimension of the filter (Covariance Matrix, State Vector)

Definition at line 61 of file imu_state.h.

Definition at line 434 of file imu_state.h.

Definition at line 432 of file imu_state.h.

Definition at line 433 of file imu_state.h.

Eigen::Vector3d imu_filter::ImuState::gravity_ [private]

Definition at line 419 of file imu_state.h.

Eigen::Vector3d imu_filter::ImuState::gyroBias_ [private]

Definition at line 413 of file imu_state.h.

Eigen::Vector3d imu_filter::ImuState::gyroBiasRange_ [private]

Definition at line 425 of file imu_state.h.

Eigen::Quaterniond imu_filter::ImuState::orientation_ [private]

Definition at line 404 of file imu_state.h.

Eigen::Vector3d imu_filter::ImuState::position_ [private]

Definition at line 407 of file imu_state.h.

Eigen::Vector3d imu_filter::ImuState::velocity_ [private]

Definition at line 410 of file imu_state.h.

Eigen::Affine3d imu_filter::ImuState::world2ImuPose_ [private]

Definition at line 436 of file imu_state.h.


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


imu_filter
Author(s): Sebastian Klose
autogenerated on Thu Dec 12 2013 11:24:43