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 "motion_model.h"
00033 
00034 constant_velocity_nh::constant_velocity_nh(double _l,double _dt,scan_matching_method _method) 
00035 {
00036         setDim(6, 0, 6, 2, 2);
00037 
00038         l=_l;
00039         dt=_dt;
00040         method=_method;
00041         
00042         static Vector x(6);
00043         double _P0[36];
00044         
00045         memset(_P0,0,sizeof(_P0));
00046         
00047         _P0[0]=100*100;
00048         _P0[7]=100*100;
00049         _P0[14]=100*100;
00050         _P0[21]=100*100;
00051         _P0[28]=100*100;
00052         _P0[35]=100*100;
00053         
00054         static Matrix P0(6,6,_P0);
00055         
00056         x(1)=0.;
00057         x(2)=0;
00058         x(3)=0;
00059         x(4)=0;
00060         x(5)=0;
00061         x(6)=0;
00062         
00063         init(x,P0);
00064 }
00065 
00066 void constant_velocity_nh::updateDt(double _dt)
00067 {
00068         dt=_dt;
00069 }
00070 
00071 void constant_velocity_nh::makeA()
00072 {
00073         double v1=x(3);
00074         double t=x(4);
00075         double f=x(5);
00076         
00077 
00078         
00079         
00080         A(1,1)=1.0;
00081         A(1,2)=0.0;
00082         A(1,3)=cos(t)*cos(f)*dt;
00083         A(1,4)=-sin(t)*cos(f)*v1*dt;
00084         A(1,5)=cos(t)*(-sin(f))*v1*dt;
00085         A(1,6)=0.0;
00086         
00087         A(2,1)=0.0;
00088         A(2,2)=1.0;
00089         A(2,3)=sin(t)*cos(f)*dt;
00090         A(2,4)=cos(t)*cos(f)*v1*dt;
00091         A(2,5)=sin(t)*(-sin(f))*v1*dt;
00092         A(2,6)=0.0;
00093         
00094         A(3,1)=0.0;
00095         A(3,2)=0.0;
00096         A(3,3)=1.0;
00097         A(3,4)=0.0;
00098         A(3,5)=0.0;
00099         A(3,6)=0.0;
00100         
00101         A(4,1)=0.0;
00102         A(4,2)=0.0;
00103         A(4,3)=sin(f/l)*dt;
00104         A(4,4)=1.0;
00105         A(4,5)=cos(f/l)/l*v1*dt;
00106         A(4,6)=0.0;
00107         
00108         A(5,1)=0.0;
00109         A(5,2)=0.0;
00110         A(5,3)=0.0;
00111         A(5,4)=0.0;
00112         A(5,5)=1.0;
00113         A(5,6)=dt;
00114         
00115         A(6,1)=0.0;
00116         A(6,2)=0.0;
00117         A(6,3)=0.0;
00118         A(6,4)=0.0;
00119         A(6,5)=0.0;
00120         A(6,6)=1.0;
00121 }
00122 
00123 void constant_velocity_nh::makeH()
00124 {
00125         H(1,1) = 0.0;
00126         H(1,2) = 0.0;
00127         H(1,3) = 1.0;
00128         H(1,4) = 0.0;
00129         H(1,5) = 0.0;
00130         H(1,6) = 0.0;
00131 
00132         H(2,1) = 0.0;
00133         H(2,2) = 0.0;
00134         H(2,3) = 0.0;
00135         H(2,4) = 0.0;
00136         H(2,5) = 1.0;
00137         H(2,6) = 0.0;
00138 }
00139 
00140 void constant_velocity_nh::makeW()
00141 {
00142         W(1,1) = 1.0;
00143         W(1,2) = 0.0;
00144         W(1,3) = 0.0;
00145         W(1,4) = 0.0;
00146         W(1,5) = 0.0;
00147         W(1,6) = 0.0;
00148         
00149         W(2,1) = 0.0;
00150         W(2,2) = 1.0;
00151         W(2,3) = 0.0;
00152         W(2,4) = 0.0;
00153         W(2,5) = 0.0;
00154         W(2,6) = 0.0;
00155         
00156         W(3,1) = 0.0;
00157         W(3,2) = 0.0;
00158         W(3,3) = 1.0;
00159         W(3,4) = 0.0;
00160         W(3,5) = 0.0;
00161         W(3,6) = 0.0;
00162         
00163         W(4,1) = 0.0;
00164         W(4,2) = 0.0;
00165         W(4,3) = 0.0;
00166         W(4,4) = 1.0;
00167         W(4,5) = 0.0;
00168         W(4,6) = 0.0;
00169         
00170         W(5,1) = 0.0;
00171         W(5,2) = 0.0;
00172         W(5,3) = 0.0;
00173         W(5,4) = 0.0;
00174         W(5,5) = 1.0;
00175         W(5,6) = 0.0;
00176         
00177         W(6,1) = 0.0;
00178         W(6,2) = 0.0;
00179         W(6,3) = 0.0;
00180         W(6,4) = 0.0;
00181         W(6,5) = 0.0;
00182         W(6,6) = 1.0;
00183 }
00184 
00185 void constant_velocity_nh::makeProcess()
00186 {
00187 
00188 
00189 
00190 
00191 
00192 
00193         
00194         Vector x_(x.size());
00195         
00196         x_(1) = x(1) + cos(x(4))*cos(x(5))*x(3)*dt;
00197         x_(2) = x(2) + sin(x(4))*cos(x(5))*x(3)*dt;
00198         x_(3) = x(3);
00199         x_(4) = x(4) + sin(x(5)/l)*x(3)*dt;
00200 
00201 
00202         
00203         x_(5) = x(5) + x(6)*dt*0.1;
00204         x_(6) = x(6);
00205         
00206         x.swap(x_);
00207 }
00208 
00209 void constant_velocity_nh::makeMeasure()
00210 {
00211         z(1)=x(3);
00212         z(2)=x(5);
00213 }
00214 
00215 void constant_velocity_nh::makeV()
00216 {
00217         V(1,1) = 1.0;
00218         V(1,2) = 0.0;
00219         V(2,1) = 0.0;
00220         V(2,2) = 1.0;
00221 }
00222 
00223 void constant_velocity_nh::makeR()
00224 {
00225 
00226 
00227         
00228 
00229 
00230 
00231 
00232 
00233 
00234 
00235 
00236 
00237 
00238 
00239 
00240 
00241 
00242 
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         switch(method)
00270         {
00271                 case MBICP:
00272 
00273 
00274                         
00275 
00276 
00277                         
00278                         R(1,1) = 0.0600;
00279                         R(1,2) = 0.0010;
00280                         
00281                         R(2,1) = 0.0010;
00282                         R(2,2) = 0.0400;
00283                          
00284                         break;
00285                         
00286                 case PSM:
00287                         
00288                         R(1,1) = 0.0600;
00289                         R(1,2) = 0.0010;
00290                         
00291                         R(2,1) = 0.0010;
00292                         R(2,2) = 0.0400;
00293                         
00294                         break;
00295                         
00296                 case PLICP:
00297                         R(1,1) = 0.0662;
00298                         R(1,2) = 0.0010;
00299                         
00300                         R(2,1) = 0.0010;
00301                         R(2,2) = 0.0217;
00302                         break;
00303         }
00304 
00305 
00306 
00307 
00308         
00309 
00310 
00311 }
00312 
00313 void constant_velocity_nh::makeQ()
00314 {
00315         double q=0;
00316 
00317         switch(method)
00318         {
00319                 case MBICP:
00320 
00321                         q=0.0015;
00322                         break;
00323                         
00324                 case PSM:
00325                         q=0.0015;
00326                         break;
00327                         
00328                 case PLICP:
00329                         q=0.0005;
00330                         break;
00331         }
00332         
00333         
00334         
00335         
00336         Q(1,1) = q;
00337         Q(1,2) = 0.0;
00338         Q(1,3) = 0.0;
00339         Q(1,4) = 0.0;
00340         Q(1,5) = 0.0;
00341         Q(1,6) = 0.0;
00342         
00343         
00344         Q(2,1) = 0.0;
00345         Q(2,2) = q;
00346         Q(2,3) = 0.0;
00347         Q(2,4) = 0.0;
00348         Q(2,5) = 0.0;
00349         Q(2,6) = 0.0;
00350         
00351         
00352         Q(3,1) = 0.0;
00353         Q(3,2) = 0.0;
00354         Q(3,3) = q*1.;
00355         Q(3,4) = 0.0;
00356         Q(3,5) = 0.0;
00357         Q(3,6) = 0.0;
00358         
00359         
00360         Q(4,1) = 0.0;
00361         Q(4,2) = 0.0;
00362         Q(4,3) = 0.0;
00363         Q(4,4) = q;
00364         Q(4,5) = 0.0;
00365         Q(4,6) = 0.0;
00366         
00367         
00368         Q(5,1) = 0.0;
00369         Q(5,2) = 0.0;
00370         Q(5,3) = 0.0;
00371         Q(5,4) = 0.0;
00372         Q(5,5) = q*1.;
00373         Q(5,6) = 0.0;
00374         
00375         
00376         Q(6,1) = 0.0;
00377         Q(6,2) = 0.0;
00378         Q(6,3) = 0.0;
00379         Q(6,4) = 0.0;
00380         Q(6,5) = 0.0;
00381         Q(6,6) = q*1.;
00382         
00383 }