KFCore.hpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, LABUST, UNIZG-FER
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the LABUST nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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                                                 //this can be optimized for constant noise models
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                                 //This can be optimized for constant R, V combinations
00101                                 this->innovationCov += VR*this->V.transpose();
00102                                 this->K = PH*this->innovationCov.inverse();
00103                                 /*
00104                                  * Correct the state estimate
00105                                  *
00106                                  * x(k) = x_(k) + K(k)*(measurement - y(k));
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                                 //Check invariant.
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                                         //Outlier rejection
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 /* KFCORE_HPP_ */
00185 #endif


labust_navigation
Author(s): Gyula Nagy
autogenerated on Fri Feb 7 2014 11:36:19