iCub-main
|
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 |
|
protected |
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.
_A | State transition matrix. |
_H | Measurement matrix. |
_Q | Process noise covariance. |
_R | Measurement noise covariance. |
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.
_A | State transition matrix. |
_B | Input matrix. |
_H | Measurement matrix. |
_Q | Process noise covariance. |
_R | Measurement noise covariance. |
const Vector & Kalman::correct | ( | const yarp::sig::Vector & | z | ) |
Corrects the current estimation of the state vector given the current measurement.
z | Current measurement. |
Definition at line 91 of file kalman.cpp.
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.
u | Current input. |
z | Current measurement. |
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.
z | Current measurement. |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
Vector Kalman::get_y | ( | ) | const |
bool Kalman::init | ( | const yarp::sig::Vector & | _x0, |
const yarp::sig::Matrix & | _P0 | ||
) |
Set initial state and error covariance.
_x0 | Initial condition for estimated state. |
_P0 | Initial condition for estimated error covariance. |
Definition at line 59 of file kalman.cpp.
|
protected |
Definition at line 24 of file kalman.cpp.
const Vector & Kalman::predict | ( | ) |
Predicts the next state vector.
Definition at line 84 of file kalman.cpp.
const yarp::sig::Vector & iCub::ctrl::Kalman::predict | ( | const yarp::sig::Vector & | u | ) |
Predicts the next state vector given the current input.
u | Current input. |
bool Kalman::set_A | ( | const yarp::sig::Matrix & | _A | ) |
Returns the state transition matrix.
_A | State transition matrix. |
Definition at line 127 of file kalman.cpp.
bool Kalman::set_B | ( | const yarp::sig::Matrix & | _B | ) |
Returns the input matrix.
_B | Input matrix. |
Definition at line 141 of file kalman.cpp.
bool Kalman::set_H | ( | const yarp::sig::Matrix & | _H | ) |
Returns the measurement transition matrix.
_H | Measurement matrix. |
Definition at line 154 of file kalman.cpp.
bool Kalman::set_Q | ( | const yarp::sig::Matrix & | _Q | ) |
Returns the process noise covariance matrix.
_Q | Process noise covariance matrix. |
Definition at line 168 of file kalman.cpp.
bool Kalman::set_R | ( | const yarp::sig::Matrix & | _R | ) |
Returns the measurement noise covariance matrix.
_R | Mearurement noise covariance matrix. |
Definition at line 181 of file kalman.cpp.