GCOP  1.0
Public Types | Public Member Functions | Public Attributes
gcop::KalmanPredictor< T, _nx, _nu, _np > Class Template Reference

#include <kalmanpredictor.h>

Inheritance diagram for gcop::KalmanPredictor< T, _nx, _nu, _np >:
Inheritance graph
[legend]
Collaboration diagram for gcop::KalmanPredictor< T, _nx, _nu, _np >:
Collaboration graph
[legend]

List of all members.

Public Types

typedef Matrix< double, _nx, 1 > Vectornd
typedef Matrix< double, _nu, 1 > Vectorcd
typedef Matrix< double, _np, 1 > Vectormd
typedef Matrix< double, _nx, _nx > Matrixnd
typedef Matrix< double, _nx, _nu > Matrixncd
typedef Matrix< double, _nu, _nx > Matrixcnd
typedef Matrix< double, _nu, _nu > Matrixcd
typedef Matrix< double, _np, _np > Matrixmd
typedef Matrix< double, _nx, _np > Matrixnmd
typedef Matrix< double, _np, _nx > Matrixmnd

Public Member Functions

 KalmanPredictor (System< T, _nx, _nu, _np > &sys)
virtual ~KalmanPredictor ()
virtual bool Predict (T &xb, double t, const T &xa, const Vectorcd &u, double h, const Vectormd *p=0, bool cov=true)

Public Attributes

Matrixnd A
 process Jacobian
Matrixnd Q
 discrete-time process noise covariance

template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
class gcop::KalmanPredictor< T, _nx, _nu, _np >


Member Typedef Documentation

template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _nu, _nu> gcop::KalmanPredictor< T, _nx, _nu, _np >::Matrixcd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _nu, _nx> gcop::KalmanPredictor< T, _nx, _nu, _np >::Matrixcnd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _np, _np> gcop::KalmanPredictor< T, _nx, _nu, _np >::Matrixmd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _np, _nx> gcop::KalmanPredictor< T, _nx, _nu, _np >::Matrixmnd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _nx, _nu> gcop::KalmanPredictor< T, _nx, _nu, _np >::Matrixncd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _nx, _nx> gcop::KalmanPredictor< T, _nx, _nu, _np >::Matrixnd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _nx, _np> gcop::KalmanPredictor< T, _nx, _nu, _np >::Matrixnmd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _nu, 1> gcop::KalmanPredictor< T, _nx, _nu, _np >::Vectorcd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _np, 1> gcop::KalmanPredictor< T, _nx, _nu, _np >::Vectormd
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
typedef Matrix<double, _nx, 1> gcop::KalmanPredictor< T, _nx, _nu, _np >::Vectornd

Constructor & Destructor Documentation

template<typename T , int _nx, int _nu, int _np>
gcop::KalmanPredictor< T, _nx, _nu, _np >::KalmanPredictor ( System< T, _nx, _nu, _np > &  sys)
template<typename T , int _nx, int _nu, int _np>
gcop::KalmanPredictor< T, _nx, _nu, _np >::~KalmanPredictor ( ) [virtual]

Member Function Documentation

template<typename T , int _nx, int _nu, int _np>
bool gcop::KalmanPredictor< T, _nx, _nu, _np >::Predict ( T &  xb,
double  t,
const T &  xa,
const Vectorcd u,
double  h,
const Vectormd p = 0,
bool  cov = true 
) [virtual]

Prediction step.

Parameters:
xbnew belief state
ttime
xaprevious belief state
ucontrol inputs
htime-step
pparameters (optional)
covwhether to update the covariance as well (true by default)
Returns:
true if success

Implements gcop::Predictor< T, _nx, _nu, _np >.


Member Data Documentation

template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
Matrixnd gcop::KalmanPredictor< T, _nx, _nu, _np >::A
template<typename T = VectorXd, int _nx = Dynamic, int _nu = Dynamic, int _np = Dynamic>
Matrixnd gcop::KalmanPredictor< T, _nx, _nu, _np >::Q

discrete-time process noise covariance

Referenced by gcop::KalmanPredictor< T, _nx, _nu, _np >::KalmanPredictor().


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