29 :
Filter<ColumnVector,ColumnVector>(prior)
30 , _Mu_new(prior->DimensionGet())
31 , _Sigma_new(prior->DimensionGet())
32 , _Sigma_temp(prior->DimensionGet(),prior->DimensionGet())
33 , _Sigma_temp_par(prior->DimensionGet(),prior->DimensionGet())
47 unsigned int meas_dimension;
48 for(
int i = 0 ; i< meas_dimensions.size(); i++)
51 meas_dimension = meas_dimensions[i];
80 _Sigma_temp.convertToSymmetricMatrix(
_Sigma_new);
131 const ColumnVector& u,
133 const ColumnVector& z,
const ColumnVector& s)
135 if (sysmodel != NULL)
139 if (measmodel != NULL)
Abstract class representing an interface for Bayesian Filters.
void PostMuSet(const MatrixWrapper::ColumnVector &c)
Set expected value of posterior estimate.
virtual ~KalmanFilter()
Destructor.
std::map< unsigned int, MeasUpdateVariables >::iterator _mapMeasUpdateVariables_it
Class representing Gaussian (or normal density)
void PostSigmaSet(const MatrixWrapper::SymmetricMatrix &s)
Set covariance of posterior estimate.
Pdf< MatrixWrapper::ColumnVector > * _post
Pointer to the Posterior Pdf.
KalmanFilter(Gaussian *prior)
Constructor.
virtual Pdf< StateVar > * PostGet()
Get Posterior density.
virtual bool UpdateInternal(SystemModel< MatrixWrapper::ColumnVector > *const sysmodel, const MatrixWrapper::ColumnVector &u, MeasurementModel< MatrixWrapper::ColumnVector, MatrixWrapper::ColumnVector > *const measmodel, const MatrixWrapper::ColumnVector &z, const MatrixWrapper::ColumnVector &s)
Actual implementation of Update, varies along filters.
virtual Gaussian * PostGet()
Get Posterior density.
void CalculateSysUpdate(const MatrixWrapper::ColumnVector &J, const MatrixWrapper::Matrix &F, const MatrixWrapper::SymmetricMatrix &Q)
std::map< unsigned int, MeasUpdateVariables > _mapMeasUpdateVariables
virtual void SysUpdate(SystemModel< MatrixWrapper::ColumnVector > *const sysmodel, const MatrixWrapper::ColumnVector &u)=0
System Update.
void CalculateMeasUpdate(const MatrixWrapper::ColumnVector &z, const MatrixWrapper::ColumnVector &Z, const MatrixWrapper::Matrix &H, const MatrixWrapper::SymmetricMatrix &R)
virtual void MeasUpdate(MeasurementModel< MatrixWrapper::ColumnVector, MatrixWrapper::ColumnVector > *const measmodel, const MatrixWrapper::ColumnVector &z, const MatrixWrapper::ColumnVector &s)=0
Measurement Update (overloaded)
void AllocateMeasModel(const vector< unsigned int > &meas_dimensions)
Function to allocate memory needed during the measurement update,.
virtual MatrixWrapper::SymmetricMatrix CovarianceGet() const
Get the Covariance Matrix E[(x - E[x])^2] of the Analytic pdf.
SymmetricMatrix _Sigma_new
virtual T ExpectedValueGet() const
Get the expected value E[x] of the pdf.