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
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00063 #include "MbICP.h"
00064 #include "MbICP2.h"
00065 #include "calcul.h"
00066 #include "sp_matrix.h"
00067 #include <stdio.h>
00068 #include <math.h>
00069 #include "percolate.h"
00070
00071 #ifndef M_PI
00072 #define M_PI 3.14159265358979323846
00073 #endif
00074
00075
00076 #define BIG_INITIAL_ERROR 1000000.0F
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096 float MAXLASERRANGE;
00097
00098
00099
00100
00101
00102
00103 TSMparams params;
00104
00105
00106 Tscan ptosRef;
00107 Tscan ptosNew;
00108
00109
00110 TAsoc cp_associations[MAXLASERPOINTS];
00111 int cntAssociationsT;
00112
00113
00114 TAsoc cp_associationsTemp[MAXLASERPOINTS];
00115 int cntAssociationsTemp;
00116
00117
00118 Tscan ptosNoView;
00119
00120
00121 Tsc motion2;
00122
00123
00124
00125
00126 static float refdqx[MAXLASERPOINTS];
00127 static float refdqx2[MAXLASERPOINTS];
00128 static float refdqy[MAXLASERPOINTS];
00129 static float refdqy2[MAXLASERPOINTS];
00130 static float distref[MAXLASERPOINTS];
00131 static float refdqxdqy[MAXLASERPOINTS];
00132
00133
00134
00135 static float error_k1;
00136 static int numConverged;
00137
00138
00139
00140
00141
00142
00143
00144
00145
00146 static void preProcessingLib(Tpfp *laserK, Tpfp *laserK1,
00147 Tsc *initialMotion);
00148
00149
00150 static int EStep();
00151
00152
00153 static int MStep(Tsc *solucion);
00154
00155
00156 static int computeMatrixLMSOpt(TAsoc *cp_ass, int cnt, Tsc *estimacion);
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168 void Init_MbICP_ScanMatching(float max_laser_range,float Bw, float Br,
00169 float L, int laserStep,
00170 float MaxDistInter,
00171 float filter,
00172 int ProjectionFilter,
00173 float AsocError,
00174 int MaxIter, float error_ratio,
00175 float error_x, float error_y, float error_t, int IterSmoothConv){
00176
00177 #ifdef INTMATSM_DEB
00178 printf("-- Init EM params . . ");
00179 #endif
00180
00181 MAXLASERRANGE = max_laser_range;
00182 params.Bw = Bw;
00183 params.Br = Br*Br;
00184 params.error_th=error_ratio;
00185 params.MaxIter=MaxIter;
00186 params.LMET=L;
00187 params.laserStep=laserStep;
00188 params.MaxDistInter=MaxDistInter;
00189 params.filter=filter;
00190 params.ProjectionFilter=ProjectionFilter;
00191 params.AsocError=AsocError;
00192 params.errx_out=error_x;
00193 params.erry_out=error_y;
00194 params.errt_out=error_t;
00195 params.IterSmoothConv=IterSmoothConv;
00196
00197 #ifdef INTMATSM_DEB
00198 printf(". OK!\n");
00199 #endif
00200
00201 }
00202
00203
00204
00205
00206
00207
00208 int MbICPmatcher(Tpfp *laserK, Tpfp *laserK1,
00209 Tsc *sensorMotion, Tsc *solution){
00210
00211 int resEStep=1;
00212 int resMStep=1;
00213 int numIteration=0;
00214
00215
00216 preProcessingLib(laserK,laserK1,sensorMotion);
00217
00218 while (numIteration<params.MaxIter){
00219
00220
00221 resEStep=EStep();;
00222
00223 if (resEStep!=1)
00224 return -1;
00225
00226
00227 resMStep=MStep(solution);
00228
00229 if (resMStep==1)
00230 return 1;
00231 else if (resMStep==-1)
00232 return -2;
00233 else
00234 numIteration++;
00235 }
00236
00237 return 2;
00238
00239 }
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00251
00252 static int EStep()
00253 {
00254 int cnt;
00255 int i,J;
00256
00257 static Tscan ptosNewRef;
00258 static int indexPtosNewRef[MAXLASERPOINTS];
00259
00260 int L,R,Io;
00261 float dist;
00262 float cp_ass_ptX,cp_ass_ptY,cp_ass_ptD;
00263 float tmp_cp_indD;
00264
00265 float q1x, q1y, q2x,q2y,p2x,p2y, dqx, dqy, dqpx, dqpy, qx, qy,dx,dy;
00266 float landaMin;
00267 float A,B,C,D;
00268 float LMET2;
00269
00270 LMET2=params.LMET*params.LMET;
00271
00272
00273
00274
00275 ptosNewRef.numPuntos=0;
00276 for (i=0; i<ptosNew.numPuntos; i++){
00277 transfor_directa_p ( ptosNew.laserC[i].x, ptosNew.laserC[i].y,
00278 &motion2, &ptosNewRef.laserC[ptosNewRef.numPuntos]);
00279 car2pol(&ptosNewRef.laserC[ptosNewRef.numPuntos],&ptosNewRef.laserP[ptosNewRef.numPuntos]);
00280 ptosNewRef.numPuntos++;
00281 }
00282
00283
00284
00285
00286
00287
00288 cnt = 1;
00289 ptosNoView.numPuntos=0;
00290 if (params.ProjectionFilter==1){
00291 for (i=1;i<ptosNewRef.numPuntos;i++){
00292 if (ptosNewRef.laserP[i].t>=ptosNewRef.laserP[cnt-1].t){
00293 ptosNewRef.laserP[cnt]=ptosNewRef.laserP[i];
00294 ptosNewRef.laserC[cnt]=ptosNewRef.laserC[i];
00295 cnt++;
00296 }
00297 else{
00298 ptosNoView.laserP[ptosNoView.numPuntos]=ptosNewRef.laserP[i];
00299 ptosNoView.laserC[ptosNoView.numPuntos]=ptosNewRef.laserC[i];
00300 ptosNoView.numPuntos++;
00301 }
00302 }
00303 ptosNewRef.numPuntos=cnt;
00304 }
00305
00306
00307
00308
00309
00310
00311
00312 L=0; R=0;
00313 Io=0;
00314
00315 if (ptosNewRef.laserP[Io].t<ptosRef.laserP[L].t) {
00316 if (ptosNewRef.laserP[Io].t + params.Bw < ptosRef.laserP[L].t){
00317 while (Io<ptosNewRef.numPuntos-1 && ptosNewRef.laserP[Io].t + params.Bw < ptosRef.laserP[L].t) {
00318 Io++;
00319 }
00320 }
00321 else{
00322 while (R<ptosRef.numPuntos-1 && ptosNewRef.laserP[Io].t + params.Bw > ptosRef.laserP[R+1].t)
00323 R++;
00324 }
00325 }
00326 else{
00327 while (L<ptosRef.numPuntos-1 && ptosNewRef.laserP[Io].t - params.Bw > ptosRef.laserP[L].t)
00328 L++;
00329 R=L;
00330 while (R<ptosRef.numPuntos-1 && ptosNewRef.laserP[Io].t + params.Bw > ptosRef.laserP[R+1].t)
00331 R++;
00332 }
00333
00334
00335
00336
00337
00338 cnt=0;
00339 for (i=Io;i<ptosNewRef.numPuntos;i++){
00340
00341
00342 cp_associations[cnt].index=indexPtosNewRef[i];
00343
00344
00345 while (L < ptosRef.numPuntos-1 && ptosNewRef.laserP[i].t - params.Bw > ptosRef.laserP[L].t)
00346 L = L + 1;
00347 while (R <ptosRef.numPuntos-1 && ptosNewRef.laserP[i].t + params.Bw > ptosRef.laserP[R+1].t)
00348 R = R + 1;
00349
00350 cp_associations[cnt].L=L;
00351 cp_associations[cnt].R=R;
00352
00353 if (L==R){
00354
00355
00356
00357 qx=ptosRef.laserC[R].x; qy=ptosRef.laserC[R].y;
00358 p2x=ptosNewRef.laserC[i].x; p2y=ptosNewRef.laserC[i].y;
00359 dx=p2x-qx; dy=p2y-qy;
00360 dist=dx*dx+dy*dy-(dx*qy-dy*qx)*(dx*qy-dy*qx)/(qx*qx+qy*qy+LMET2);
00361
00362 if (dist<params.Br){
00363 cp_associations[cnt].nx=ptosNewRef.laserC[i].x;
00364 cp_associations[cnt].ny=ptosNewRef.laserC[i].y;
00365 cp_associations[cnt].rx=ptosRef.laserC[R].x;
00366 cp_associations[cnt].ry=ptosRef.laserC[R].y;
00367 cp_associations[cnt].dist=dist;
00368 cnt++;
00369 }
00370 }
00371 else if (L<R)
00372 {
00373
00374
00375 cp_ass_ptX=0;
00376 cp_ass_ptY=0;
00377 cp_ass_ptD=100000;
00378
00379
00380 for (J=L+1;J<=R;J++){
00381
00382
00383 q1x=ptosRef.laserC[J-1].x; q1y=ptosRef.laserC[J-1].y;
00384 q2x=ptosRef.laserC[J].x; q2y=ptosRef.laserC[J].y;
00385 p2x=ptosNewRef.laserC[i].x; p2y=ptosNewRef.laserC[i].y;
00386
00387 dqx=refdqx[J-1]; dqy=refdqy[J-1];
00388 dqpx=q1x-p2x; dqpy=q1y-p2y;
00389 A=1/(p2x*p2x+p2y*p2y+LMET2);
00390 B=(1-A*p2y*p2y);
00391 C=(1-A*p2x*p2x);
00392 D=A*p2x*p2y;
00393
00394 landaMin=(D*(dqx*dqpy+dqy*dqpx)+B*dqx*dqpx+C*dqy*dqpy)/(B*refdqx2[J-1]+C*refdqy2[J-1]+2*D*refdqxdqy[J-1]);
00395
00396 if (landaMin<0){
00397 qx=q1x; qy=q1y;}
00398 else if (landaMin>1){
00399 qx=q2x; qy=q2y;}
00400 else if (distref[J-1]<params.MaxDistInter) {
00401 qx=(1-landaMin)*q1x+landaMin*q2x;
00402 qy=(1-landaMin)*q1y+landaMin*q2y;
00403 }
00404 else{
00405 if (landaMin<0.5){
00406 qx=q1x; qy=q1y;}
00407 else{
00408 qx=q2x; qy=q2y;}
00409 }
00410
00411
00412 dx=p2x-qx;
00413 dy=p2y-qy;
00414 tmp_cp_indD=dx*dx+dy*dy-(dx*qy-dy*qx)*(dx*qy-dy*qx)/(qx*qx+qy*qy+LMET2);
00415
00416
00417 if (tmp_cp_indD < cp_ass_ptD){
00418 cp_ass_ptX=qx;
00419 cp_ass_ptY=qy;
00420 cp_ass_ptD=tmp_cp_indD;
00421 }
00422 }
00423
00424
00425 if (cp_ass_ptD< params.Br){
00426 cp_associations[cnt].nx=ptosNewRef.laserC[i].x;
00427 cp_associations[cnt].ny=ptosNewRef.laserC[i].y;
00428 cp_associations[cnt].rx=cp_ass_ptX;
00429 cp_associations[cnt].ry=cp_ass_ptY;
00430 cp_associations[cnt].dist=cp_ass_ptD;
00431
00432 cnt++;
00433 }
00434 }
00435 else {
00436 cp_associations[cnt].nx=ptosNewRef.laserC[i].x;
00437 cp_associations[cnt].ny=ptosNewRef.laserC[i].y;
00438 cp_associations[cnt].rx=0;
00439 cp_associations[cnt].ry=0;
00440 cp_associations[cnt].dist=params.Br;
00441 cnt++;
00442 }
00443 }
00444
00445 cntAssociationsT=cnt;
00446
00447
00448 if (cntAssociationsT<ptosNewRef.numPuntos*params.AsocError){
00449 #ifdef INTMATSM_DEB
00450 printf("Number of associations too low <%d out of %f>\n",
00451 cntAssociationsT,ptosNewRef.numPuntos*params.AsocError);
00452 #endif
00453 return 0;
00454 }
00455
00456 return 1;
00457 }
00458
00459
00460
00461
00462
00463
00464 static int MStep(Tsc *solucion){
00465
00466 Tsc estim_cp;
00467 int i,cnt,res;
00468 float error_ratio, error;
00469 float cosw, sinw, dtx, dty, tmp1, tmp2;
00470 static TAsoc cp_tmp[MAXLASERPOINTS+1];
00471
00472
00473
00474
00475 if (params.filter<1){
00476
00477
00478 for (i=0;i<cntAssociationsT;i++){
00479 cp_tmp[i+1]=cp_associations[i];
00480 }
00481 cp_tmp[0].dist=-1;
00482
00483 heapsort(cp_tmp, cntAssociationsT);
00484
00485 cnt=((int)(cntAssociationsT*100*params.filter))/100;
00486
00487 for (i=0;i<cnt;i++){
00488 cp_associationsTemp[i]=cp_tmp[i+1];
00489 }
00490 }
00491 else{
00492 cnt=0;
00493 for (i=0; i<cntAssociationsT;i++){
00494 if (cp_associations[i].dist<params.Br){
00495 cp_associationsTemp[cnt]=cp_associations[i];
00496 cnt++;
00497 }
00498 }
00499 }
00500
00501 cntAssociationsTemp=cnt;
00502
00503 #ifdef INTMATSM_DEB
00504 printf("All assoc: %d Filtered: %d Percentage: %f\n",
00505 cntAssociationsT, cntAssociationsTemp, cntAssociationsTemp*100.0/cntAssociationsT);
00506 #endif
00507
00508
00509
00510
00511
00512 res=computeMatrixLMSOpt(cp_associationsTemp,cnt,&estim_cp);
00513 if (res==-1)
00514 return -1;
00515
00516 #ifdef INTMATSM_DEB
00517 printf("estim_cp: <%f %f %f>\n",estim_cp.x, estim_cp.y,estim_cp.tita);
00518 printf("New impl: <%f %f %f>\n",estim_cp.x, estim_cp.y,estim_cp.tita);
00519 #endif
00520
00521 cosw=(float)cos(estim_cp.tita); sinw=(float)sin(estim_cp.tita);
00522 dtx=estim_cp.x; dty=estim_cp.y;
00523
00524
00525
00526
00527
00528 error=0;
00529 for (i = 0; i<cnt;i++){
00530 tmp1=cp_associationsTemp[i].nx * cosw - cp_associationsTemp[i].ny * sinw + dtx - cp_associationsTemp[i].rx;tmp1*=tmp1;
00531 tmp2=cp_associationsTemp[i].nx * sinw + cp_associationsTemp[i].ny * cosw + dty - cp_associationsTemp[i].ry;tmp2*=tmp2;
00532 error = error+ tmp1+tmp2;
00533 }
00534
00535 error_ratio = error / error_k1;
00536
00537 #ifdef INTMATSM_DEB
00538 printf("<err,errk1,errRatio>=<%f,%f,%f>\n estim=<%f,%f,%f>\n",
00539 error,error_k1,error_ratio, estim_cp.x,estim_cp.y, estim_cp.tita);
00540 #endif
00541
00542
00543
00544
00545 if (fabs(1.0-error_ratio)<=params.error_th ||
00546 (fabs(estim_cp.x)<params.errx_out && fabs(estim_cp.y)<params.erry_out
00547 && fabs(estim_cp.tita)<params.errt_out) ){
00548 numConverged++;
00549 }
00550 else
00551 numConverged=0;
00552
00553
00554
00555 composicion_sis(&estim_cp, &motion2, solucion);
00556 motion2=*solucion;
00557 error_k1=error;
00558
00559
00560 if (numConverged>params.IterSmoothConv)
00561 return 1;
00562 else
00563 return 0;
00564 }
00565
00566
00567
00568
00569
00570
00571 static int computeMatrixLMSOpt(TAsoc *cp_ass, int cnt, Tsc *estimacion) {
00572
00573 int i;
00574 float LMETRICA2;
00575 float X1[MAXLASERPOINTS], Y1[MAXLASERPOINTS];
00576 float X2[MAXLASERPOINTS],Y2[MAXLASERPOINTS];
00577 float X2Y2[MAXLASERPOINTS],X1X2[MAXLASERPOINTS];
00578 float X1Y2[MAXLASERPOINTS], Y1X2[MAXLASERPOINTS];
00579 float Y1Y2[MAXLASERPOINTS];
00580 float K[MAXLASERPOINTS], DS[MAXLASERPOINTS];
00581 float DsD[MAXLASERPOINTS], X2DsD[MAXLASERPOINTS], Y2DsD[MAXLASERPOINTS];
00582 float Bs[MAXLASERPOINTS], BsD[MAXLASERPOINTS];
00583 float A1, A2, A3, B1, B2, B3, C1, C2, C3, D1, D2, D3;
00584 MATRIX matA,invMatA;
00585 VECTOR vecB,vecSol;
00586
00587 A1=0;A2=0;A3=0;B1=0;B2=0;B3=0;
00588 C1=0;C2=0;C3=0;D1=0;D2=0;D3=0;
00589
00590
00591 LMETRICA2=params.LMET*params.LMET;
00592
00593 for (i=0; i<cnt; i++){
00594 X1[i]=cp_ass[i].nx*cp_ass[i].nx;
00595 Y1[i]=cp_ass[i].ny*cp_ass[i].ny;
00596 X2[i]=cp_ass[i].rx*cp_ass[i].rx;
00597 Y2[i]=cp_ass[i].ry*cp_ass[i].ry;
00598 X2Y2[i]=cp_ass[i].rx*cp_ass[i].ry;
00599
00600 X1X2[i]=cp_ass[i].nx*cp_ass[i].rx;
00601 X1Y2[i]=cp_ass[i].nx*cp_ass[i].ry;
00602 Y1X2[i]=cp_ass[i].ny*cp_ass[i].rx;
00603 Y1Y2[i]=cp_ass[i].ny*cp_ass[i].ry;
00604
00605 K[i]=X2[i]+Y2[i] + LMETRICA2;
00606 DS[i]=Y1Y2[i] + X1X2[i];
00607 DsD[i]=DS[i]/K[i];
00608 X2DsD[i]=cp_ass[i].rx*DsD[i];
00609 Y2DsD[i]=cp_ass[i].ry*DsD[i];
00610
00611 Bs[i]=X1Y2[i]-Y1X2[i];
00612 BsD[i]=Bs[i]/K[i];
00613
00614 A1=A1 + (1-Y2[i]/K[i]);
00615 B1=B1 + X2Y2[i]/K[i];
00616 C1=C1 + (-cp_ass[i].ny + Y2DsD[i]);
00617 D1=D1 + (cp_ass[i].nx - cp_ass[i].rx -cp_ass[i].ry*BsD[i]);
00618
00619 A2=B1;
00620 B2=B2 + (1-X2[i]/K[i]);
00621 C2=C2 + (cp_ass[i].nx-X2DsD[i]);
00622 D2=D2 + (cp_ass[i].ny -cp_ass[i].ry +cp_ass[i].rx*BsD[i]);
00623
00624 A3=C1;
00625 B3=C2;
00626 C3=C3 + (X1[i] + Y1[i] - DS[i]*DS[i]/K[i]);
00627 D3=D3 + (Bs[i]*(-1+DsD[i]));
00628 }
00629
00630
00631 initialize_matrix(&matA,3,3);
00632 MDATA(matA,0,0)=A1; MDATA(matA,0,1)=B1; MDATA(matA,0,2)=C1;
00633 MDATA(matA,1,0)=A2; MDATA(matA,1,1)=B2; MDATA(matA,1,2)=C2;
00634 MDATA(matA,2,0)=A3; MDATA(matA,2,1)=B3; MDATA(matA,2,2)=C3;
00635
00636 if (inverse_matrix (&matA, &invMatA)==-1)
00637 return -1;
00638
00639 #ifdef INTMATSM_DEB
00640 print_matrix("inverted matrix", &invMatA);
00641 #endif
00642
00643 initialize_vector(&vecB,3);
00644 VDATA(vecB,0)=D1; VDATA(vecB,1)=D2; VDATA(vecB,2)=D3;
00645 multiply_matrix_vector (&invMatA, &vecB, &vecSol);
00646
00647 estimacion->x=-VDATA(vecSol,0);
00648 estimacion->y=-VDATA(vecSol,1);
00649 estimacion->tita=-VDATA(vecSol,2);
00650
00651 return 1;
00652 }
00653
00654
00655
00656
00657
00658
00659 static void preProcessingLib(Tpfp *laserK, Tpfp *laserK1,
00660 Tsc *initialMotion)
00661 {
00662
00663 int i,j;
00664
00665 motion2=*initialMotion;
00666
00667
00668
00669 ptosNew.numPuntos=0;
00670 for (i=0; i<MAXLASERPOINTS; i++) {
00671 if (laserK1[i].r <MAXLASERRANGE){
00672 ptosNew.laserP[ptosNew.numPuntos].r=laserK1[i].r;
00673 ptosNew.laserP[ptosNew.numPuntos].t=laserK1[i].t;
00674 ptosNew.laserC[ptosNew.numPuntos].x=(float)(laserK1[i].r * cos(laserK1[i].t));
00675 ptosNew.laserC[ptosNew.numPuntos].y=(float)(laserK1[i].r * sin(laserK1[i].t));
00676 ptosNew.numPuntos++;
00677 }
00678 }
00679
00680
00681 j=0;
00682 for (i=0; i<ptosNew.numPuntos; i+=params.laserStep) {
00683 ptosNew.laserC[j]=ptosNew.laserC[i];
00684 j++;
00685 }
00686 ptosNew.numPuntos=j;
00687
00688
00689 ptosRef.numPuntos=0;
00690 for (i=0; i<MAXLASERPOINTS; i++) {
00691 if (laserK[i].r <MAXLASERRANGE){
00692 ptosRef.laserP[ptosRef.numPuntos].r=laserK[i].r;
00693 ptosRef.laserP[ptosRef.numPuntos].t=laserK[i].t;
00694 ptosRef.laserC[ptosRef.numPuntos].x=(float)(laserK[i].r * cos(laserK1[i].t));
00695 ptosRef.laserC[ptosRef.numPuntos].y=(float)(laserK[i].r * sin(laserK1[i].t));
00696 ptosRef.numPuntos++;
00697 }
00698 }
00699
00700
00701 j=0;
00702 for (i=0; i<ptosRef.numPuntos; i+=params.laserStep) {
00703 ptosRef.laserC[j]=ptosRef.laserC[i];
00704 j++;
00705 }
00706 ptosRef.numPuntos=j;
00707
00708
00709
00710 for (i=0;i<ptosRef.numPuntos-1;i++) {
00711 car2pol(&ptosRef.laserC[i],&ptosRef.laserP[i]);
00712 refdqx[i]=ptosRef.laserC[i].x - ptosRef.laserC[i+1].x;
00713 refdqy[i]=ptosRef.laserC[i].y - ptosRef.laserC[i+1].y;
00714 refdqx2[i]=refdqx[i]*refdqx[i];
00715 refdqy2[i]=refdqy[i]*refdqy[i];
00716 distref[i]=refdqx2[i] + refdqy2[i];
00717 refdqxdqy[i]=refdqx[i]*refdqy[i];
00718 }
00719 car2pol(&ptosRef.laserC[ptosRef.numPuntos-1],&ptosRef.laserP[ptosRef.numPuntos-1]);
00720
00721 error_k1=BIG_INITIAL_ERROR;
00722 numConverged=0;
00723 }