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 #include <mtt/mht_types.h>
00033 #error This file should not be used, DEPRECATED
00034 
00035 long association_errors = 0;
00036 
00037 void constantVelocityEKFilter::SetIdentity(Matrix& M,int size,double value)
00038 {
00039         for(int l=0;l<size;l++)
00040                 for(int c=0;c<size;c++)
00041                         if(c==l)
00042                                 M(l,c)=value;
00043                         else
00044                                 M(l,c)=0;
00045 }
00046 
00047 void constantVelocityEKFilter::SetZero(Matrix& M,int size)
00048 {
00049         for(int l=0;l<size;l++)
00050                 for(int c=0;c<size;c++)
00051                         M(l,c)=0;
00052 }
00053 
00054 void constantVelocityEKFilter::InitFilter(Vector4d& x_init)
00055 {
00056         setDim(4,0,4,2,2);
00057         dt=1./50.;
00058         lt=Time::now();
00059         
00060         Vector x_0(4);
00061 
00062         x_0(0)=x_init(0);
00063         x_0(1)=x_init(1);
00064         x_0(2)=x_init(2);
00065         x_0(3)=x_init(3);
00066         
00067         Matrix P_0(4,4);
00068         
00069         miss_associations=0;
00070         
00071         
00072         SetIdentity(P_0,4,2.0);
00073         
00074         init(x_0,P_0);
00075         
00076 
00077 
00078 
00079         
00080 
00081 
00082 }
00083 
00084 void constantVelocityEKFilter::InitFilter(Vector4d& x_init,Matrix4d& P_init)
00085 {
00086         setDim(4,0,4,2,2);
00087         dt=1./50.;
00088         lt=Time::now();
00089         
00090         Vector x_0(4);
00091 
00092         x_0(0)=x_init(0);
00093         x_0(1)=x_init(1);
00094         x_0(2)=x_init(2);
00095         x_0(3)=x_init(3);
00096         
00097         Matrix P_0(4,4);
00098         
00099         P_0(0,0)=P_init(0,0);
00100         P_0(0,1)=P_init(0,1);
00101         P_0(0,2)=P_init(0,2);
00102         P_0(0,3)=P_init(0,3);
00103         
00104         P_0(1,0)=P_init(1,0);
00105         P_0(1,1)=P_init(1,1);
00106         P_0(1,2)=P_init(1,2);
00107         P_0(1,3)=P_init(1,3);
00108         
00109         P_0(2,0)=P_init(2,0);
00110         P_0(2,1)=P_init(2,1);
00111         P_0(2,2)=P_init(2,2);
00112         P_0(2,3)=P_init(2,3);
00113         
00114         P_0(3,0)=P_init(3,0);
00115         P_0(3,1)=P_init(3,1);
00116         P_0(3,2)=P_init(3,2);
00117         P_0(3,3)=P_init(3,3);
00118         
00119 
00120 
00121 
00122         
00123         init(x_0,P_0);
00124         
00125 
00126 
00127 
00128         
00129 }
00130 
00131 void constantVelocityEKFilter::makeCommonProcess()
00132 {
00133         dt=1./50.;              
00134 }
00135 
00136 void constantVelocityEKFilter::makeBaseA()
00137 {
00138         A(0,0)=1.0;
00139         A(0,1)=0.0;
00140 
00141         A(0,3)=0.0;
00142 
00143         A(1,0)=0.0;
00144         A(1,1)=1.0;
00145         A(1,2)=0.0;
00146 
00147         
00148         A(2,0)=0.0;
00149         A(2,1)=0.0;
00150         A(2,2)=1.0;
00151         A(2,3)=0.0;
00152         
00153         A(3,0)=0.0;
00154         A(3,1)=0.0;
00155         A(3,2)=0.0;
00156         A(3,3)=1.0;
00157 }
00158 
00159 void constantVelocityEKFilter::makeA()
00160 {
00161         A(0,2)=dt;
00162         A(1,3)=dt;
00163 }
00164 
00165 void constantVelocityEKFilter::makeBaseH()
00166 {
00167         H(0,0) = 1.0;
00168         H(0,1) = 0.0;
00169         H(1,1) = 1.0;
00170         H(1,0) = 0.0;
00171 }
00172 
00173 void constantVelocityEKFilter::makeBaseW()
00174 {
00175         SetIdentity(W,4,1.0);
00176 }
00177 
00178 void constantVelocityEKFilter::makeBaseV()
00179 {
00180         SetIdentity(V,2,1.0);
00181 }
00182 
00183 void constantVelocityEKFilter::makeR()
00184 {
00185         
00186 
00187         
00188         Matrix2d eigval;
00189         
00190         double inovation_factor = 3.0;
00191         double distortion_y = 0.1;
00192         
00193         double x_min = 0.2;
00194         double y_min = 0.2;
00195         
00196         double x_size = inovation_error.norm()*inovation_factor;
00197         double y_size = inovation_error.norm()*inovation_factor*distortion_y;
00198         
00199         double dir = atan2(inovation_error(1),inovation_error(0));
00200 
00201         
00202         if(miss_associations>0)
00203         {
00204                 x_size+=5;
00205                 y_size+=5;
00206         }
00207 
00208         
00209 
00210 
00211 
00212 
00213 
00214 
00215 
00216 
00217 
00218 
00219 
00220 
00221 
00222 
00223 
00224 
00225         
00226 
00227         
00228         if(y_size<y_min)
00229                 y_size = y_min;
00230         
00231         if(x_size<x_min)
00232                 x_size = x_min;
00233         
00234                                 
00235         eigval << x_size,               0,
00236                                    0,  y_size;
00237                         
00238         Matrix2d rot; 
00239         rot << cos(dir), -sin(dir),
00240                    sin(dir), cos(dir);
00241 
00242         Matrix2d cov = rot*eigval*rot.inverse();
00243         
00244 
00245 
00246 
00247 
00248 
00249 
00250 
00251 
00252 
00253 
00254 
00255 
00256 
00257 
00258 
00259 
00260 
00261 
00262 
00263 
00264 
00265 
00266 
00267 
00268 
00269 
00270 
00271 
00272 
00273 
00274 
00275 
00276 
00277 
00278 
00279 
00280         R(0,0) = cov(0,0);
00281         R(0,1) = cov(0,1);
00282 
00283         R(1,0) = cov(1,0);
00284         R(1,1) = cov(1,1);
00285 
00286         
00287 
00288 }
00289 
00290 void constantVelocityEKFilter::makeQ()
00291 {
00292         SetZero(Q,4);
00293 
00294 
00295 
00296 
00297 
00298         
00299         double sigma;
00300         
00301         if(life_time<10)
00302                 sigma=150;
00303         else if(life_time>12)
00304                 sigma=100;
00305         else if(life_time<15)
00306                 sigma=50;
00307         else
00308                 sigma=10;
00309                 
00310         
00311         double factor=pow(sigma,2)*dt/6.;
00312 
00313         Q(0,0)=factor*2*pow(dt,2);
00314         Q(1,1)=factor*2*pow(dt,2);
00315         
00316         Q(0,2)=factor*3*pow(dt,1);
00317         Q(2,1)=factor*3*pow(dt,1);
00318         
00319         Q(1,3)=factor*3*pow(dt,1);
00320         Q(3,1)=factor*3*pow(dt,1);
00321         
00322         Q(2,2)=factor*6;
00323         Q(3,3)=factor*6;
00324 }
00325 
00326 void constantVelocityEKFilter::makeProcess()
00327 {
00328         Vector x_(x.size());
00329         
00330         x_(0) = x(0) + x(2)*dt;
00331         x_(1) = x(1) + x(3)*dt;
00332         x_(2) = x(2);
00333         x_(3) = x(3);
00334 
00335         x.swap(x_);
00336 }
00337 
00338 void constantVelocityEKFilter::makeMeasure()
00339 {
00340         z(0)=x(0); 
00341         z(1)=x(1); 
00342 }