Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef KFCORE_HPP_
00035 #define KFCORE_HPP_
00036 #include <labust/navigation/KFBase.hpp>
00037
00038 #include <vector>
00039 #include <cassert>
00040
00042 #include <iostream>
00043
00044 namespace labust
00045 {
00046 namespace navigation
00047 {
00052 template <class Model>
00053 class KFCore : public KFBase< Model >
00054 {
00055 typedef KFBase< Model > Base;
00056 public:
00060 KFCore(){};
00061
00067 void predict(typename Base::inputref u = typename Model::input_type())
00068 {
00069 assert((this->Ts) && "KFCore: Sampling time set to zero." );
00074 this->step(u);
00079 this->P = this->A*this->P*this->A.transpose() +
00080
00081 this->W*this->Q*this->W.transpose();
00082 }
00090 typename Base::vectorref correct(typename Base::outputref y_meas)
00091 {
00097 typename Base::matrix PH = this->P*this->H.transpose();
00098 this->innovationCov = this->H*PH;
00099 typename Base::matrix VR = this->V*this->R;
00100
00101 this->innovationCov += VR*this->V.transpose();
00102 this->K = PH*this->innovationCov.inverse();
00103
00104
00105
00106
00107
00108 typename Base::output_type y;
00109 this->estimate_y(y);
00110 this->innovation = y_meas - y;
00111 this->x += this->K*this->innovation;
00116 typename Base::matrix IKH = Base::matrix::Identity(this->P.rows(), this->P.cols());
00117 IKH -= this->K*this->H;
00118 this->P = IKH*this->P;
00119
00120 return this->xk_1 = this->x;
00121 }
00122
00130 template <class NewMeasVector>
00131 typename Base::vectorref correct(
00132 typename Base::outputref measurements,
00133 NewMeasVector& newMeas,
00134 bool reject_outliers = true)
00135 {
00136
00137 assert(measurements.size() == Model::stateNum &&
00138 newMeas.size() == Model::stateNum);
00139
00140 std::vector<size_t> arrived;
00141 std::vector<typename Model::numericprecission> dataVec;
00142
00143 for (size_t i=0; i<newMeas.size(); ++i)
00144 {
00145
00146 if (newMeas(i) && reject_outliers)
00147 {
00148 double dist=fabs(this->x(i) - measurements(i));
00149 newMeas(i) = (dist <= sqrt(this->P(i,i)) + sqrt(this->R0(i,i)));
00150
00152 if (!newMeas(i))
00153 {
00154 std::cerr<<"Outlier rejected: x(i)="<<this->x(i);
00155 std::cerr<<", m(i)="<<measurements(i);
00156 std::cerr<<", r(i)="<<sqrt(this->P(i,i)) + sqrt(this->R0(i,i));
00157 }
00158 }
00159
00160 if (newMeas(i))
00161 {
00162 arrived.push_back(i);
00163 dataVec.push_back(measurements(i));
00164 newMeas(i) = 0;
00165 }
00166 }
00167
00168 typename Base::output_type y_meas(arrived.size());
00169 this->H = Model::matrix::Zero(arrived.size(),Model::stateNum);
00170 this->V = Model::matrix::Zero(arrived.size(),Model::stateNum);
00171
00172 for (size_t i=0; i<arrived.size();++i)
00173 {
00174 y_meas(i) = dataVec[i];
00175 this->H.row(i) = this->H0.row(arrived[i]);
00176 this->V.row(i) = this->V0.row(arrived[i]);
00177 }
00178
00179 return this->correct(y_meas);
00180 }
00181 };
00182 };
00183 }
00184
00185 #endif