Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes
imu_filter::Observation Class Reference

#include <observation.h>

Inheritance diagram for imu_filter::Observation:
Inheritance graph
[legend]

List of all members.

Public Types

typedef Eigen::Matrix< double,
Dimension, Dimension
CovMat
typedef Eigen::Matrix< double,
Dimension, ImuState::Dimension
JacMat
typedef Eigen::Matrix< double,
Dimension, 1 > 
Vector

Public Member Functions

const Eigen::Affine3d & body2ImuTransform () const
 Retrieve the transformation from target frame to IMU frame.
const CovMatcovariance () const
 access to the observation covariance matrix
const JacMatjacobian () const
 access to the observation jacobian matrix
const Eigen::Affine3d & lastWorld2Imu () const
 get back the last stored IMU pose estimate
 Observation ()
void set (const Vector &v)
 set the current observation in vector form
void setBody2ImuTransform (const Eigen::Quaterniond &q, const Eigen::Vector3d &t)
 Set the transformation from the target frame to the IMU.
void setBody2ImuTransform (const Eigen::Affine3d &T)
 Set the transformation from the target frame to the IMU.
void setCovariance (const CovMat &covariance)
 set the observation covariance matrix
void setCovarianceFromStdDev (const Vector &stdDevs)
 set the diagonal of the observation covariance from std. deviations
virtual void updateJacobian (const ImuState &state)=0
 pure virtual function, that should update the observation jacobian according to the current state
void updateLastStateInformation (const ImuState &state)
 remember this IMU state information to create a pseudo measurement later on
const Vectorvector () const
 get the current observation in vector form
virtual ~Observation ()

Static Public Attributes

static const size_t Dimension = 7

Protected Member Functions

void computeDeltaFromAbsolute (const Eigen::Affine3d &currentObservation)
void updateObservationFromDelta ()

Protected Attributes

Eigen::Affine3d body2ImuTransform_
Eigen::Affine3d deltaTransform_
Eigen::Affine3d lastBodyTransform_
Eigen::Affine3d lastWorld2Imu_
CovMat measCov_
JacMat measJacobian_
Vector observation_

Detailed Description

Definition at line 48 of file observation.h.


Member Typedef Documentation

typedef Eigen::Matrix<double, Dimension, Dimension> imu_filter::Observation::CovMat

Definition at line 53 of file observation.h.

Definition at line 54 of file observation.h.

typedef Eigen::Matrix<double, Dimension, 1> imu_filter::Observation::Vector

Definition at line 52 of file observation.h.


Constructor & Destructor Documentation

Definition at line 56 of file observation.h.

virtual imu_filter::Observation::~Observation ( ) [inline, virtual]

Definition at line 67 of file observation.h.


Member Function Documentation

const Eigen::Affine3d& imu_filter::Observation::body2ImuTransform ( ) const [inline]

Retrieve the transformation from target frame to IMU frame.

Definition at line 130 of file observation.h.

void imu_filter::Observation::computeDeltaFromAbsolute ( const Eigen::Affine3d &  currentObservation) [inline, protected]

Definition at line 171 of file observation.h.

const CovMat& imu_filter::Observation::covariance ( ) const [inline]

access to the observation covariance matrix

Definition at line 102 of file observation.h.

const JacMat& imu_filter::Observation::jacobian ( ) const [inline]

access to the observation jacobian matrix

Definition at line 107 of file observation.h.

const Eigen::Affine3d& imu_filter::Observation::lastWorld2Imu ( ) const [inline]

get back the last stored IMU pose estimate

Definition at line 148 of file observation.h.

void imu_filter::Observation::set ( const Vector v) [inline]

set the current observation in vector form

Parameters:
vthe current observation

Definition at line 75 of file observation.h.

void imu_filter::Observation::setBody2ImuTransform ( const Eigen::Quaterniond &  q,
const Eigen::Vector3d &  t 
) [inline]

Set the transformation from the target frame to the IMU.

Parameters:
qrotation from target frame to IMU frame
ttranslation from target frame to IMU frame

Definition at line 115 of file observation.h.

void imu_filter::Observation::setBody2ImuTransform ( const Eigen::Affine3d &  T) [inline]

Set the transformation from the target frame to the IMU.

Parameters:
Ttransformation from target frame to IMU frame

Definition at line 125 of file observation.h.

void imu_filter::Observation::setCovariance ( const CovMat covariance) [inline]

set the observation covariance matrix

Parameters:
covarianceobservation covariance

Definition at line 86 of file observation.h.

void imu_filter::Observation::setCovarianceFromStdDev ( const Vector stdDevs) [inline]

set the diagonal of the observation covariance from std. deviations

Parameters:
stdDevsstandard deviations of the observations

Definition at line 92 of file observation.h.

virtual void imu_filter::Observation::updateJacobian ( const ImuState state) [pure virtual]

pure virtual function, that should update the observation jacobian according to the current state

Implemented in imu_filter::VOObservation.

remember this IMU state information to create a pseudo measurement later on

The orientation and position of the IMU state will be stored, in order to create a relative transformation estimate later on.

Parameters:
statethe IMU state we want to remember

Definition at line 139 of file observation.h.

Definition at line 177 of file observation.h.

const Vector& imu_filter::Observation::vector ( ) const [inline]

get the current observation in vector form

Definition at line 80 of file observation.h.


Member Data Documentation

Eigen::Affine3d imu_filter::Observation::body2ImuTransform_ [protected]

Definition at line 160 of file observation.h.

Eigen::Affine3d imu_filter::Observation::deltaTransform_ [protected]

Definition at line 168 of file observation.h.

const size_t imu_filter::Observation::Dimension = 7 [static]

Definition at line 51 of file observation.h.

Eigen::Affine3d imu_filter::Observation::lastBodyTransform_ [protected]

Definition at line 162 of file observation.h.

Eigen::Affine3d imu_filter::Observation::lastWorld2Imu_ [protected]

Definition at line 165 of file observation.h.

Definition at line 157 of file observation.h.

Definition at line 158 of file observation.h.

Definition at line 156 of file observation.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