GCOP
1.0
|
00001 #ifndef GCOP_PREDICTOR_H 00002 #define GCOP_PREDICTOR_H 00003 00004 #include "system.h" 00005 00006 namespace gcop { 00007 00008 template <typename T = VectorXd, 00009 int _nx = Dynamic, 00010 int _nu = Dynamic, 00011 int _np = Dynamic> class Predictor { 00012 public: 00013 00014 typedef Matrix<double, _nx, 1> Vectornd; 00015 typedef Matrix<double, _nu, 1> Vectorcd; 00016 typedef Matrix<double, _np, 1> Vectormd; 00017 00018 typedef Matrix<double, _nx, _nx> Matrixnd; 00019 typedef Matrix<double, _nx, _nu> Matrixncd; 00020 typedef Matrix<double, _nu, _nx> Matrixcnd; 00021 typedef Matrix<double, _nu, _nu> Matrixcd; 00022 00023 typedef Matrix<double, _np, _np> Matrixmd; 00024 typedef Matrix<double, _nx, _np> Matrixnmd; 00025 typedef Matrix<double, _np, _nx> Matrixmnd; 00026 00031 Predictor(System<T, _nx, _nu, _np> &sys); 00032 00033 virtual ~Predictor(); 00034 00046 virtual bool Predict(T& xb, double t, const T &xa, 00047 const Vectorcd &u, double h, 00048 const Vectormd *p = 0, bool cov = true) = 0; 00049 00050 00051 System<T, _nx, _nu, _np> &sys; 00052 00053 }; 00054 00055 00056 template <typename T, int _nx, int _nu, int _np> 00057 Predictor<T, _nx, _nu, _np>::Predictor( System<T, _nx, _nu, _np> &sys) : 00058 sys(sys) { 00059 } 00060 00061 template <typename T, int _nx, int _nu, int _np> 00062 Predictor<T, _nx, _nu, _np>::~Predictor() { 00063 } 00064 00065 } 00066 00067 00068 #endif