iCub-main
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
iCub::ctrl::Kalman Class Reference

Classic Kalman estimator. More...

#include <kalman.h>

Public Member Functions

 Kalman (const yarp::sig::Matrix &_A, const yarp::sig::Matrix &_H, const yarp::sig::Matrix &_Q, const yarp::sig::Matrix &_R)
 Init a Kalman state estimator.
 
 Kalman (const yarp::sig::Matrix &_A, const yarp::sig::Matrix &_B, const yarp::sig::Matrix &_H, const yarp::sig::Matrix &_Q, const yarp::sig::Matrix &_R)
 Init a Kalman state estimator.
 
bool init (const yarp::sig::Vector &_x0, const yarp::sig::Matrix &_P0)
 Set initial state and error covariance.
 
const yarp::sig::Vector & predict (const yarp::sig::Vector &u)
 Predicts the next state vector given the current input.
 
const yarp::sig::Vector & predict ()
 Predicts the next state vector.
 
const yarp::sig::Vector & correct (const yarp::sig::Vector &z)
 Corrects the current estimation of the state vector given the current measurement.
 
const yarp::sig::Vector & filt (const yarp::sig::Vector &u, const yarp::sig::Vector &z)
 Returns the estimated state vector given the current input and the current measurement by performing a prediction and then correcting the result.
 
const yarp::sig::Vector & filt (const yarp::sig::Vector &z)
 Returns the estimated state vector given the current measurement by performing a prediction and then correcting the result.
 
const yarp::sig::Vector & get_x () const
 Returns the estimated state.
 
yarp::sig::Vector get_y () const
 Returns the estimated output.
 
const yarp::sig::Matrix & get_P () const
 Returns the estimated state covariance.
 
const yarp::sig::Matrix & get_S () const
 Returns the estimated measurement covariance.
 
double get_ValidationGate () const
 Returns the validation gate.
 
const yarp::sig::Matrix & get_K () const
 Returns the Kalman gain matrix.
 
const yarp::sig::Matrix & get_A () const
 Returns the state transition matrix.
 
const yarp::sig::Matrix & get_B () const
 Returns the input matrix.
 
const yarp::sig::Matrix & get_H () const
 Returns the measurement matrix.
 
const yarp::sig::Matrix & get_Q () const
 Returns the process noise covariance matrix.
 
const yarp::sig::Matrix & get_R () const
 Returns the measurement noise covariance matrix.
 
bool set_A (const yarp::sig::Matrix &_A)
 Returns the state transition matrix.
 
bool set_B (const yarp::sig::Matrix &_B)
 Returns the input matrix.
 
bool set_H (const yarp::sig::Matrix &_H)
 Returns the measurement transition matrix.
 
bool set_Q (const yarp::sig::Matrix &_Q)
 Returns the process noise covariance matrix.
 
bool set_R (const yarp::sig::Matrix &_R)
 Returns the measurement noise covariance matrix.
 

Protected Member Functions

void initialize ()
 
 Kalman ()
 

Protected Attributes

yarp::sig::Matrix A
 
yarp::sig::Matrix At
 
yarp::sig::Matrix H
 
yarp::sig::Matrix Ht
 
yarp::sig::Matrix B
 
yarp::sig::Matrix Q
 
yarp::sig::Matrix R
 
yarp::sig::Matrix I
 
yarp::sig::Vector x
 
yarp::sig::Matrix P
 
yarp::sig::Matrix K
 
yarp::sig::Matrix S
 
double validationGate
 
size_t n
 
size_t m
 

Detailed Description

Classic Kalman estimator.

Definition at line 41 of file kalman.h.

Constructor & Destructor Documentation

◆ Kalman() [1/3]

iCub::ctrl::Kalman::Kalman ( )
protected

◆ Kalman() [2/3]

iCub::ctrl::Kalman::Kalman ( const yarp::sig::Matrix &  _A,
const yarp::sig::Matrix &  _H,
const yarp::sig::Matrix &  _Q,
const yarp::sig::Matrix &  _R 
)

Init a Kalman state estimator.

Parameters
_AState transition matrix.
_HMeasurement matrix.
_QProcess noise covariance.
_RMeasurement noise covariance.

◆ Kalman() [3/3]

iCub::ctrl::Kalman::Kalman ( const yarp::sig::Matrix &  _A,
const yarp::sig::Matrix &  _B,
const yarp::sig::Matrix &  _H,
const yarp::sig::Matrix &  _Q,
const yarp::sig::Matrix &  _R 
)

Init a Kalman state estimator.

Parameters
_AState transition matrix.
_BInput matrix.
_HMeasurement matrix.
_QProcess noise covariance.
_RMeasurement noise covariance.

Member Function Documentation

◆ correct()

const Vector & Kalman::correct ( const yarp::sig::Vector &  z)

Corrects the current estimation of the state vector given the current measurement.

Parameters
zCurrent measurement.
Returns
Estimated state vector.

Definition at line 91 of file kalman.cpp.

◆ filt() [1/2]

const yarp::sig::Vector & iCub::ctrl::Kalman::filt ( const yarp::sig::Vector &  u,
const yarp::sig::Vector &  z 
)

Returns the estimated state vector given the current input and the current measurement by performing a prediction and then correcting the result.

Parameters
uCurrent input.
zCurrent measurement.
Returns
Estimated state vector.

◆ filt() [2/2]

const yarp::sig::Vector & iCub::ctrl::Kalman::filt ( const yarp::sig::Vector &  z)

Returns the estimated state vector given the current measurement by performing a prediction and then correcting the result.

Parameters
zCurrent measurement.
Returns
Estimated state vector.

◆ get_A()

const yarp::sig::Matrix & iCub::ctrl::Kalman::get_A ( ) const
inline

Returns the state transition matrix.

Returns
State transition matrix.

Definition at line 197 of file kalman.h.

◆ get_B()

const yarp::sig::Matrix & iCub::ctrl::Kalman::get_B ( ) const
inline

Returns the input matrix.

Returns
Input matrix.

Definition at line 204 of file kalman.h.

◆ get_H()

const yarp::sig::Matrix & iCub::ctrl::Kalman::get_H ( ) const
inline

Returns the measurement matrix.

Returns
Measurement matrix.

Definition at line 211 of file kalman.h.

◆ get_K()

const yarp::sig::Matrix & iCub::ctrl::Kalman::get_K ( ) const
inline

Returns the Kalman gain matrix.

Returns
Kalman gain matrix.

Definition at line 190 of file kalman.h.

◆ get_P()

const yarp::sig::Matrix & iCub::ctrl::Kalman::get_P ( ) const
inline

Returns the estimated state covariance.

Returns
Estimated state covariance.

Definition at line 167 of file kalman.h.

◆ get_Q()

const yarp::sig::Matrix & iCub::ctrl::Kalman::get_Q ( ) const
inline

Returns the process noise covariance matrix.

Returns
Process noise covariance matrix.

Definition at line 218 of file kalman.h.

◆ get_R()

const yarp::sig::Matrix & iCub::ctrl::Kalman::get_R ( ) const
inline

Returns the measurement noise covariance matrix.

Returns
Measurement noise covariance matrix.

Definition at line 225 of file kalman.h.

◆ get_S()

const yarp::sig::Matrix & iCub::ctrl::Kalman::get_S ( ) const
inline

Returns the estimated measurement covariance.

Returns
Estimated measurement covariance.

Definition at line 174 of file kalman.h.

◆ get_ValidationGate()

double iCub::ctrl::Kalman::get_ValidationGate ( ) const
inline

Returns the validation gate.

Note
The validation gate is meaningful only after correction.
See also
correct
Returns
validation gate.

Definition at line 183 of file kalman.h.

◆ get_x()

const yarp::sig::Vector & iCub::ctrl::Kalman::get_x ( ) const
inline

Returns the estimated state.

Returns
Estimated state.

Definition at line 153 of file kalman.h.

◆ get_y()

Vector Kalman::get_y ( ) const

Returns the estimated output.

Returns
Estimated output.

Definition at line 120 of file kalman.cpp.

◆ init()

bool Kalman::init ( const yarp::sig::Vector &  _x0,
const yarp::sig::Matrix &  _P0 
)

Set initial state and error covariance.

Parameters
_x0Initial condition for estimated state.
_P0Initial condition for estimated error covariance.
Returns
true/false on success/failure.

Definition at line 59 of file kalman.cpp.

◆ initialize()

void Kalman::initialize ( )
protected

Definition at line 24 of file kalman.cpp.

◆ predict() [1/2]

const Vector & Kalman::predict ( )

Predicts the next state vector.

Returns
Estimated state vector.

Definition at line 84 of file kalman.cpp.

◆ predict() [2/2]

const yarp::sig::Vector & iCub::ctrl::Kalman::predict ( const yarp::sig::Vector &  u)

Predicts the next state vector given the current input.

Parameters
uCurrent input.
Returns
Estimated state vector.

◆ set_A()

bool Kalman::set_A ( const yarp::sig::Matrix &  _A)

Returns the state transition matrix.

Parameters
_AState transition matrix.
Returns
true/false on success/failure.

Definition at line 127 of file kalman.cpp.

◆ set_B()

bool Kalman::set_B ( const yarp::sig::Matrix &  _B)

Returns the input matrix.

Parameters
_BInput matrix.
Returns
true/false on success/failure.

Definition at line 141 of file kalman.cpp.

◆ set_H()

bool Kalman::set_H ( const yarp::sig::Matrix &  _H)

Returns the measurement transition matrix.

Parameters
_HMeasurement matrix.
Returns
true/false on success/failure.

Definition at line 154 of file kalman.cpp.

◆ set_Q()

bool Kalman::set_Q ( const yarp::sig::Matrix &  _Q)

Returns the process noise covariance matrix.

Parameters
_QProcess noise covariance matrix.
Returns
true/false on success/failure.

Definition at line 168 of file kalman.cpp.

◆ set_R()

bool Kalman::set_R ( const yarp::sig::Matrix &  _R)

Returns the measurement noise covariance matrix.

Parameters
_RMearurement noise covariance matrix.
Returns
true/false on success/failure.

Definition at line 181 of file kalman.cpp.

Member Data Documentation

◆ A

yarp::sig::Matrix iCub::ctrl::Kalman::A
protected

Definition at line 44 of file kalman.h.

◆ At

yarp::sig::Matrix iCub::ctrl::Kalman::At
protected

Definition at line 44 of file kalman.h.

◆ B

yarp::sig::Matrix iCub::ctrl::Kalman::B
protected

Definition at line 46 of file kalman.h.

◆ H

yarp::sig::Matrix iCub::ctrl::Kalman::H
protected

Definition at line 45 of file kalman.h.

◆ Ht

yarp::sig::Matrix iCub::ctrl::Kalman::Ht
protected

Definition at line 45 of file kalman.h.

◆ I

yarp::sig::Matrix iCub::ctrl::Kalman::I
protected

Definition at line 49 of file kalman.h.

◆ K

yarp::sig::Matrix iCub::ctrl::Kalman::K
protected

Definition at line 53 of file kalman.h.

◆ m

size_t iCub::ctrl::Kalman::m
protected

Definition at line 58 of file kalman.h.

◆ n

size_t iCub::ctrl::Kalman::n
protected

Definition at line 57 of file kalman.h.

◆ P

yarp::sig::Matrix iCub::ctrl::Kalman::P
protected

Definition at line 52 of file kalman.h.

◆ Q

yarp::sig::Matrix iCub::ctrl::Kalman::Q
protected

Definition at line 47 of file kalman.h.

◆ R

yarp::sig::Matrix iCub::ctrl::Kalman::R
protected

Definition at line 48 of file kalman.h.

◆ S

yarp::sig::Matrix iCub::ctrl::Kalman::S
protected

Definition at line 54 of file kalman.h.

◆ validationGate

double iCub::ctrl::Kalman::validationGate
protected

Definition at line 55 of file kalman.h.

◆ x

yarp::sig::Vector iCub::ctrl::Kalman::x
protected

Definition at line 51 of file kalman.h.


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