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 
00032 #ifndef _NONHOLONOMICKALMANFILTER_H_
00033 #define _NONHOLONOMICKALMANFILTER_H_
00034 
00035 #include <algorithm>
00036 #include <vector>
00037 #include <iostream>
00038 
00039 #include <ros/ros.h>
00040 
00041 #include <boost/shared_ptr.hpp>
00042 #include <boost/format.hpp>
00043 
00044 #include <Eigen/Dense>
00045 #include <Eigen/Cholesky>
00046 
00047 #include <kfilter/ekfilter.hpp>
00048 
00049 using Eigen::Matrix4d;
00050 using Eigen::Matrix2d;
00051 using Eigen::Vector2d;
00052 using Eigen::Vector4d;
00053 using Eigen::MatrixXd;
00054 using Eigen::VectorXd;
00055 
00056 using namespace Kalman;
00057 using namespace ros;
00058 using namespace std;
00059 
00060 typedef Eigen::Matrix<double, 5, 1> Vector5d;
00061 typedef Eigen::Matrix<double, 3, 1> Vector3d;
00062 typedef Eigen::Matrix<double, 5, 5> Matrix5d;
00063 
00064 
00065 typedef EKFilter<double,0,false,false,false>::Vector kVector;
00066 typedef EKFilter<double,0,false,false,false>::Matrix kMatrix;
00067 
00068 class nonholonomicEKFilter;
00069 typedef boost::shared_ptr<nonholonomicEKFilter> nonholonomicEKFilterPtr;
00070 
00075 class nonholonomicEKFilter:public EKFilter<double,0,false,false,false>
00076 {
00077         public:
00078                 
00088                 void SetIdentity(kMatrix& M,int size,double value=1)
00089                 {
00090                         for(int l=0;l<size;l++)
00091                                 for(int c=0;c<size;c++)
00092                                         if(c==l)
00093                                                 M(l,c)=value;
00094                                         else
00095                                                 M(l,c)=0;
00096                 }
00097 
00098                 
00107                 void SetZero(kMatrix& M,int size)
00108                 {
00109                         for(int l=0;l<size;l++)
00110                                 for(int c=0;c<size;c++)
00111                                         M(l,c)=0;
00112                 }
00113                 
00120                 void InitFilter(Vector5d& x_init)
00121                 {
00122                         setDim(5,0,5,3,3);
00123                         dt=1./50.;
00124                         lt=Time::now();
00125                         
00126                         Vector x_0(5);
00127 
00128                         x_0(0)=x_init(0);
00129                         x_0(1)=x_init(1);
00130                         x_0(2)=x_init(2);
00131                         x_0(3)=x_init(3);
00132                         x_0(4)=x_init(4);
00133                         
00134                         Matrix P_0(5,5);
00135                         
00136                         miss_associations=0;
00137                         
00138                         
00139                         SetIdentity(P_0,5,4.0);
00140                         
00141                         init(x_0,P_0);
00142                 }
00143                 
00144                 void InitFilter(Vector5d& x_init,Matrix5d& P_init)
00145                 {
00146                         setDim(5,0,5,3,3);
00147                         dt=1./50.;
00148                         lt=Time::now();
00149                         
00150                         Vector x_0(5);
00151 
00152                         x_0(0)=x_init(0);
00153                         x_0(1)=x_init(1);
00154                         x_0(2)=x_init(2);
00155                         x_0(3)=x_init(3);
00156                         x_0(4)=x_init(4);
00157                         
00158                         Matrix P_0(5,5);
00159                         
00160                         P_0(0,0)=P_init(0,0);
00161                         P_0(0,1)=P_init(0,1);
00162                         P_0(0,2)=P_init(0,2);
00163                         P_0(0,3)=P_init(0,3);
00164                         P_0(0,4)=P_init(0,4);
00165                         
00166                         P_0(1,0)=P_init(1,0);
00167                         P_0(1,1)=P_init(1,1);
00168                         P_0(1,2)=P_init(1,2);
00169                         P_0(1,3)=P_init(1,3);
00170                         P_0(1,4)=P_init(1,4);
00171                         
00172                         P_0(2,0)=P_init(2,0);
00173                         P_0(2,1)=P_init(2,1);
00174                         P_0(2,2)=P_init(2,2);
00175                         P_0(2,3)=P_init(2,3);
00176                         P_0(2,4)=P_init(2,4);
00177                         
00178                         P_0(3,0)=P_init(3,0);
00179                         P_0(3,1)=P_init(3,1);
00180                         P_0(3,2)=P_init(3,2);
00181                         P_0(3,3)=P_init(3,3);
00182                         P_0(3,4)=P_init(3,4);
00183                         
00184                         P_0(4,0)=P_init(4,0);
00185                         P_0(4,1)=P_init(4,1);
00186                         P_0(4,2)=P_init(4,2);
00187                         P_0(4,3)=P_init(4,3);
00188                         P_0(4,4)=P_init(4,4);
00189                         
00190                         init(x_0,P_0);
00191                         
00192                 }
00193                 
00194                 int miss_associations;
00195                 int life_time;
00196                 
00197                 Vector5d x_predicted;
00198                 Vector3d z_measured;
00199                 Vector3d inovation_error;
00200                 
00201         protected:
00202                 
00204                 double dt;
00206                 Time lt;
00207                 
00208                 double l;
00209                 
00215                 void makeCommonProcess()
00216                 {
00217                         dt=1./50.;              
00218                         l=2.5;
00219                 }
00220                 
00224                 void makeA()
00225                 {
00226                         double v=x(2);
00227                         double t=x(3);
00228                         double f=x(4);
00229                         
00230                         A(0,0)=1.0;
00231                         A(0,1)=0.0;
00232                         A(0,2)=cos(t)*cos(f)*dt;
00233                         A(0,3)=-sin(t)*cos(f)*v*dt;
00234                         A(0,4)=cos(t)*(-sin(f))*v*dt;
00235                         
00236                         A(1,0)=0.0;
00237                         A(1,1)=1.0;
00238                         A(1,2)=sin(t)*cos(f)*dt;
00239                         A(1,3)=cos(t)*cos(f)*v*dt;
00240                         A(1,4)=sin(t)*(-sin(f))*v*dt;
00241                         
00242                         A(2,0)=0.0;
00243                         A(2,1)=0.0;
00244                         A(2,2)=1.0;
00245                         A(2,3)=0.0;
00246                         A(2,4)=0.0;
00247                         
00248                         A(3,0)=0.0;
00249                         A(3,1)=0.0;
00250                         A(3,2)=sin(f)*dt/l;
00251                         A(3,3)=1.0;
00252                         A(3,4)=cos(f)/l*v*dt;
00253                         
00254                         A(4,0)=0.0;
00255                         A(4,1)=0.0;
00256                         A(4,2)=0.0;
00257                         A(4,3)=0.0;
00258                         A(4,4)=1.0;
00259                 }
00260                 
00264                 void makeH()
00265                 {
00266 
00267 
00268                                 H(0,0) = 1;
00269                                 H(0,1) = 0;
00270                                 H(0,2) = 0;
00271                                 H(0,3) = 0;
00272                                 H(0,4) = 0;
00273 
00274                                 H(1,0) = 0;
00275                                 H(1,1) = 1;
00276                                 H(1,2) = 0;
00277                                 H(1,3) = 0;
00278                                 H(1,4) = 0;
00279                                 
00280                                 H(2,0) = 0;
00281                                 H(2,1) = 0;
00282                                 H(2,2) = 0;
00283                                 H(2,3) = 1;
00284                                 H(2,4) = 0;
00285 
00286 
00287 
00288 
00289 
00290 
00291 
00292 
00293 
00294 
00295 
00296 
00297 
00298 
00299 
00300 
00301 
00302 
00303 
00304 
00305 
00306                         
00307                 }
00308                 
00312                 void makeBaseW()
00313                 {
00314                         SetIdentity(W,5,1.0);
00315                 }
00316         
00320                 void makeBaseV()
00321                 {
00322                         SetIdentity(V,3,1.0);
00323                 }
00324 
00328                 void makeR()
00329                 {
00330                         Matrix2d eigval;
00331         
00332                         double inovation_factor = 5.0;
00333                         double distortion_y = 0.1;
00334         
00335                         double x_min = 0.2;
00336                         double y_min = 0.2;
00337         
00338                         double x_max = 6.0;
00339                         double y_max = 6.0;
00340                         
00341                         double x_size = inovation_error.norm()*inovation_factor;
00342                         double y_size = inovation_error.norm()*inovation_factor*distortion_y;
00343         
00344                         double dir = atan2(inovation_error(1),inovation_error(0));
00345 
00346                         cout<<"miss_associations: "<<miss_associations<<endl;
00347         
00348                         if(miss_associations>0)
00349                         {
00350                                 x_size+=20;
00351                                 y_size+=20;
00352                         }
00353 
00354                         if(y_size<y_min)
00355                                 y_size = y_min;
00356                         
00357                         if(x_size<x_min)
00358                                 x_size = x_min;
00359                         
00360                         if(y_size>y_max)
00361                                 y_size = y_max;
00362                         
00363                         if(x_size>x_max)
00364                                 x_size = x_max;
00365                         
00366                         eigval << x_size,               0,
00367                                                 0,  y_size;
00368                                         
00369                         Matrix2d rot; 
00370                         rot << cos(dir), -sin(dir),
00371                                 sin(dir), cos(dir);
00372 
00373                         Matrix2d cov = rot*eigval*rot.inverse();
00374                         
00375                         R(0,0) = cov(0,0);
00376                         R(0,1) = cov(0,1);
00377                 
00378                         R(1,0) = cov(1,0);
00379                         R(1,1) = cov(1,1);
00380                         
00381 
00382 
00383                         R(0,2) = 0.000;
00384                         
00385 
00386 
00387                         R(1,2) = 0.000;
00388                         
00389                         R(2,0) = 0.000;
00390                         R(2,1) = 0.000;
00391                         R(2,2) = 0.010;
00392                 }
00393 
00397                 void makeQ()
00398                 {
00399                         double q=2.0;
00400                 
00401                         
00402                         Q(0,0) = q*0.1;
00403                         Q(0,1) = 0.0;
00404                         Q(0,2) = 0.0;
00405                         Q(0,3) = 0.0;
00406                         Q(0,4) = 0.0;
00407                         
00408                         
00409                         Q(1,0) = 0.0;
00410                         Q(1,1) = q*0.1;
00411                         Q(1,2) = 0.0;
00412                         Q(1,3) = 0.0;
00413                         Q(1,4) = 0.0;
00414                         
00415                         
00416                         Q(2,0) = 0.0;
00417                         Q(2,1) = 0.0;
00418                         Q(2,2) = q*20.;
00419                         Q(2,3) = 0.0;
00420                         Q(2,4) = 0.0;
00421                         
00422                         
00423                         Q(3,0) = 0.0;
00424                         Q(3,1) = 0.0;
00425                         Q(3,2) = 0.0;
00426                         Q(3,3) = q*0.01;
00427                         Q(3,4) = 0.0;
00428                         
00429                         
00430                         Q(4,0) = 0.0;
00431                         Q(4,1) = 0.0;
00432                         Q(4,2) = 0.0;
00433                         Q(4,3) = 0.0;
00434                         Q(4,4) = q*0.01;
00435                         
00436                 }
00437 
00441                 void makeProcess()
00442                 {
00443                         
00444                 
00445                 
00446                 
00447                 
00448                 
00449                         
00450                         Vector x_(x.size());
00451                         
00452                         x_(0) = x(0) + cos(x(3))*cos(x(4))*x(2)*dt;
00453                         x_(1) = x(1) + sin(x(3))*cos(x(4))*x(2)*dt;
00454                         x_(2) = x(2);
00455                         x_(3) = x(3) + sin(x(4))*x(2)*dt/l;
00456                         x_(4) = x(4);
00457                         
00458                         
00459                         x.swap(x_);
00460                 }
00461                 
00465                 void makeMeasure()
00466                 {
00467                         z(0)=x(0);
00468                         z(1)=x(1);
00469                         z(2)=x(3);
00470                 }
00471 };
00472 
00473 #endif