00001 // ---------------------------------------------------------------------------- 00002 // 00003 // $Id$ 00004 // 00005 // Copyright 2008, 2009, 2010, 2011, 2012 Antonio Franchi and Paolo Stegagno 00006 // 00007 // This file is part of MIP. 00008 // 00009 // MIP is free software: you can redistribute it and/or modify 00010 // it under the terms of the GNU General Public License as published by 00011 // the Free Software Foundation, either version 3 of the License, or 00012 // (at your option) any later version. 00013 // 00014 // MIP is distributed in the hope that it will be useful, 00015 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00016 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00017 // GNU General Public License for more details. 00018 // 00019 // You should have received a copy of the GNU General Public License 00020 // along with MIP. If not, see <http://www.gnu.org/licenses/>. 00021 // 00022 // Contact info: antonio.franchi@tuebingen.mpg.de stegagno@diag.uniroma1.it 00023 // 00024 // ---------------------------------------------------------------------------- 00025 00026 00030 00032 /* @{ */ 00033 00034 #ifndef __PA_FIL_BFL_RR_NOMR_H_ 00035 #define __PA_FIL_BFL_RR_NOMR_H_ 00036 00037 #include <filter/bootstrapfilter.h> 00038 00039 #include <model/systemmodel.h> 00040 #include <model/measurementmodel.h> 00041 00042 00043 #include <iostream> 00044 #include <fstream> 00045 00046 #include <pdf/conditionalpdf.h> 00047 #include <pdf/gaussian.h> 00048 #include "PaFilBFL.h" 00049 00050 using namespace MatrixWrapper; 00051 using namespace BFL; 00052 using namespace std; 00053 00054 00055 namespace MipAlgorithms { 00057 class NonlinearMobileRobRelRelNoMRPdf : public ConditionalPdf<MatrixWrapper::ColumnVector, MatrixWrapper::ColumnVector> { 00058 public: 00061 NonlinearMobileRobRelRelNoMRPdf( const Gaussian& additiveNoise); 00062 00064 virtual ~NonlinearMobileRobRelRelNoMRPdf(); 00065 00066 // implement this virtual function for system model of a particle filter 00067 virtual bool SampleFrom (Sample<MatrixWrapper::ColumnVector>& one_sample, int method=DEFAULT, void * args=NULL) const; 00068 00069 private: 00070 Gaussian _additiveNoise; 00071 }; 00072 00073 00075 class NonlinearMeasurementRelRelNoMRPdf : public ConditionalPdf<MatrixWrapper::ColumnVector, MatrixWrapper::ColumnVector> { 00076 public: 00079 NonlinearMeasurementRelRelNoMRPdf( const Gaussian& measNoise); 00080 00082 virtual ~NonlinearMeasurementRelRelNoMRPdf(); 00083 00084 // implement this virtual function for measurement model of a particle filter 00085 virtual Probability ProbabilityGet(const MatrixWrapper::ColumnVector& measurement) const; 00086 00087 private: 00088 Gaussian _measNoise; 00089 }; 00090 00091 00095 class PaFilBFLRelRelNoMR : public PaFilBFL{ 00096 public: 00097 00099 PaFilBFLRelRelNoMR(PaFilBFLPar par); 00100 00102 ~PaFilBFLRelRelNoMR(); 00103 00106 void step(MutLocFilInput &input); 00107 00109 void reset(); 00110 00112 string print(); 00113 00114 private: 00115 00116 Decimal _iniTime; 00117 00118 PaFilBFLPar _par; 00119 00120 NonlinearMobileRobRelRelNoMRPdf* _sys_pdf; 00121 SystemModel<ColumnVector>* _sys_model; 00122 00123 NonlinearMeasurementRelRelNoMRPdf* _meas_pdf; 00124 MeasurementModel<ColumnVector, ColumnVector>* _meas_model; 00125 00126 Pose _myPrevConf; 00127 Pose _myCurrConf; 00128 Pose _myOdometry; 00129 00130 Pose _hisPrevConf; 00131 Pose _hisCurrConf; 00132 Pose _hisOdometry; 00133 00134 Decimal _myOdometryNorm; 00135 Decimal _hisOdometryNorm; 00136 00137 void _normalStep(MutLocFilInput &input); 00138 00139 void _firstStep(MutLocFilInput &input); 00140 00141 void _computeHisOdometry(MutLocFilInput &input); 00142 00143 }; 00144 } 00145 00146 #endif 00147 00148 00149 00150 00151 00152