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 #include <iostream>
00030 using namespace std;
00031
00032 #include "../sbpl/headers.h"
00033
00034 #if MEM_CHECK == 1
00035 void DisableMemCheck()
00036 {
00037
00038
00039 int tmpFlag = _CrtSetDbgFlag( _CRTDBG_REPORT_FLAG );
00040
00041
00042 tmpFlag |= _CRTDBG_DELAY_FREE_MEM_DF;
00043
00044
00045 tmpFlag &= ~_CRTDBG_ALLOC_MEM_DF;
00046
00047
00048 _CrtSetDbgFlag( tmpFlag );
00049
00050 }
00051
00052 void EnableMemCheck()
00053 {
00054
00055
00056 int tmpFlag = _CrtSetDbgFlag( _CRTDBG_REPORT_FLAG );
00057
00058
00059 tmpFlag |= _CRTDBG_DELAY_FREE_MEM_DF;
00060
00061
00062 tmpFlag |= _CRTDBG_ALLOC_MEM_DF;
00063
00064
00065 _CrtSetDbgFlag( tmpFlag );
00066
00067 }
00068 #endif
00069
00070 void checkmdpstate(CMDPSTATE* state)
00071 {
00072 #if DEBUG == 0
00073 SBPL_ERROR("ERROR: checkMDPstate is too expensive for not in DEBUG mode\n");
00074 throw new SBPL_Exception();
00075 #endif
00076
00077 for(int aind = 0; aind < (int)state->Actions.size(); aind++)
00078 {
00079 for(int aind1 = 0; aind1 < (int)state->Actions.size(); aind1++)
00080 {
00081 if(state->Actions[aind1]->ActionID == state->Actions[aind]->ActionID &&
00082 aind1 != aind)
00083 {
00084 SBPL_ERROR("ERROR in CheckMDP: multiple actions with the same ID exist\n");
00085 throw new SBPL_Exception();
00086 }
00087 }
00088 for(int sind = 0; sind < (int)state->Actions[aind]->SuccsID.size(); sind++)
00089 {
00090 for(int sind1 = 0; sind1 < (int)state->Actions[aind]->SuccsID.size(); sind1++)
00091 {
00092 if(state->Actions[aind]->SuccsID[sind] == state->Actions[aind]->SuccsID[sind1] &&
00093 sind != sind1)
00094 {
00095 SBPL_ERROR("ERROR in CheckMDP: multiple outcomes with the same ID exist\n");
00096 throw new SBPL_Exception();
00097 }
00098 }
00099 }
00100 }
00101 }
00102
00103
00104 void CheckMDP(CMDP* mdp)
00105 {
00106 for(int i = 0; i < (int)mdp->StateArray.size(); i++)
00107 {
00108 checkmdpstate(mdp->StateArray[i]);
00109 }
00110 }
00111
00112
00113
00114
00115 void PrintMatrix(int** matrix, int rows, int cols, FILE* fOut)
00116 {
00117 for(int r = 0; r < rows; r++)
00118 {
00119 for(int c = 0; c < cols; c++)
00120 {
00121 SBPL_FPRINTF(fOut, "%d ", matrix[r][c]);
00122 }
00123 SBPL_FPRINTF(fOut, "\n");
00124 }
00125 }
00126
00127
00128
00129 bool PathExists(CMDP* pMarkovChain, CMDPSTATE* sourcestate, CMDPSTATE* targetstate)
00130 {
00131 CMDPSTATE* state;
00132 vector<CMDPSTATE*> WorkList;
00133 int i;
00134 bool *bProcessed = new bool [pMarkovChain->StateArray.size()];
00135 bool bFound = false;
00136
00137
00138 WorkList.push_back(sourcestate);
00139 while((int)WorkList.size() > 0)
00140 {
00141
00142 state = WorkList[WorkList.size()-1];
00143 WorkList.pop_back();
00144
00145
00146 if((int)state->Actions.size() > 1)
00147 {
00148 SBPL_ERROR("ERROR in PathExists: Markov Chain is a general MDP\n");
00149 throw new SBPL_Exception();
00150 }
00151
00152 if(state == targetstate)
00153 {
00154
00155 bFound = true;
00156 break;
00157 }
00158
00159
00160 for(int sind = 0; (int)state->Actions.size() != 0 && sind < (int)state->Actions[0]->SuccsID.size(); sind++)
00161 {
00162
00163 for(i = 0; i < (int)pMarkovChain->StateArray.size(); i++)
00164 {
00165 if(pMarkovChain->StateArray[i]->StateID == state->Actions[0]->SuccsID[sind])
00166 break;
00167 }
00168 if(i == (int)pMarkovChain->StateArray.size())
00169 {
00170 SBPL_ERROR("ERROR in PathExists: successor is not found\n");
00171 throw new SBPL_Exception();
00172 }
00173 CMDPSTATE* SuccState = pMarkovChain->StateArray[i];
00174
00175
00176 if(!bProcessed[i])
00177 {
00178 bProcessed[i] = true;
00179 WorkList.push_back(SuccState);
00180 }
00181 }
00182 }
00183
00184 delete [] bProcessed;
00185
00186 return bFound;
00187 }
00188
00189 int ComputeNumofStochasticActions(CMDP* pMDP)
00190 {
00191 int i;
00192 int nNumofStochActions = 0;
00193 SBPL_PRINTF("ComputeNumofStochasticActions...\n");
00194
00195 for(i = 0; i < (int)pMDP->StateArray.size(); i++)
00196 {
00197 for(int aind = 0; aind < (int)pMDP->StateArray[i]->Actions.size(); aind++)
00198 {
00199 if((int)pMDP->StateArray[i]->Actions[aind]->SuccsID.size() > 1)
00200 nNumofStochActions++;
00201 }
00202 }
00203 SBPL_PRINTF("done\n");
00204
00205 return nNumofStochActions;
00206 }
00207
00208
00209 void EvaluatePolicy(CMDP* PolicyMDP, int StartStateID, int GoalStateID,
00210 double* PolValue, bool *bFullPolicy, double* Pcgoal, int *nMerges,
00211 bool* bCycles)
00212 {
00213 int i, j, startind=-1;
00214 double delta = INFINITECOST;
00215 double mindelta = 0.1;
00216
00217 *Pcgoal = 0;
00218 *nMerges = 0;
00219
00220 SBPL_PRINTF("Evaluating policy...\n");
00221
00222
00223 double* vals = new double [PolicyMDP->StateArray.size()];
00224 double* Pcvals = new double [PolicyMDP->StateArray.size()];
00225 for(i = 0; i < (int)PolicyMDP->StateArray.size(); i++)
00226 {
00227 vals[i] = 0;
00228 Pcvals[i] = 0;
00229
00230
00231 if(PolicyMDP->StateArray[i]->StateID == StartStateID)
00232 {
00233 startind = i;
00234 Pcvals[i] = 1;
00235 }
00236 }
00237
00238
00239 *bFullPolicy = true;
00240 bool bFirstIter = true;
00241 while(delta > mindelta)
00242 {
00243 delta = 0;
00244 for(i = 0; i < (int)PolicyMDP->StateArray.size(); i++)
00245 {
00246
00247 CMDPSTATE* state = PolicyMDP->StateArray[i];
00248
00249
00250 if(state->StateID == GoalStateID)
00251 {
00252 vals[i] = 0;
00253 }
00254 else if((int)state->Actions.size() == 0)
00255 {
00256 *bFullPolicy = false;
00257 vals[i] = UNKNOWN_COST;
00258 *PolValue = vals[startind];
00259 return;
00260 }
00261 else
00262 {
00263
00264 CMDPACTION* action = state->Actions[0];
00265
00266
00267 double Q = 0;
00268 for(int oind = 0; oind < (int)action->SuccsID.size(); oind++)
00269 {
00270
00271 for(j = 0; j < (int)PolicyMDP->StateArray.size(); j++)
00272 {
00273 if(PolicyMDP->StateArray[j]->StateID == action->SuccsID[oind])
00274 break;
00275 }
00276 if(j == (int)PolicyMDP->StateArray.size())
00277 {
00278 SBPL_ERROR("ERROR in EvaluatePolicy: incorrect successor %d\n",
00279 action->SuccsID[oind]);
00280 throw new SBPL_Exception();
00281 }
00282 Q += action->SuccsProb[oind]*(vals[j] + action->Costs[oind]);
00283 }
00284
00285 if(vals[i] > Q)
00286 {
00287 SBPL_ERROR("ERROR in EvaluatePolicy: val is decreasing\n");
00288 throw new SBPL_Exception();
00289 }
00290
00291
00292 if(delta < Q - vals[i])
00293 delta = Q-vals[i];
00294
00295
00296 vals[i] = Q;
00297 }
00298
00299
00300 double Pc = 0;
00301
00302 int nMerge = 0;
00303 for(j = 0; j < (int)PolicyMDP->StateArray.size(); j++)
00304 {
00305 for(int oind = 0; (int)PolicyMDP->StateArray[j]->Actions.size() > 0 &&
00306 oind < (int)PolicyMDP->StateArray[j]->Actions[0]->SuccsID.size(); oind++)
00307 {
00308 if(PolicyMDP->StateArray[j]->Actions[0]->SuccsID[oind] == state->StateID)
00309 {
00310
00311 double PredPc = Pcvals[j];
00312 double OutProb = PolicyMDP->StateArray[j]->Actions[0]->SuccsProb[oind];
00313
00314
00315 Pc = Pc + OutProb*PredPc;
00316 nMerge++;
00317
00318
00319 if(bFirstIter && !(*bCycles))
00320 {
00321 if(PathExists(PolicyMDP, state, PolicyMDP->StateArray[j]))
00322 *bCycles = true;
00323 }
00324 }
00325 }
00326 }
00327 if(bFirstIter && state->StateID != GoalStateID && nMerge > 0)
00328 *nMerges += (nMerge-1);
00329
00330
00331 if(state->StateID != StartStateID)
00332 Pcvals[i] = Pc;
00333
00334 if(state->StateID == GoalStateID)
00335 *Pcgoal = Pcvals[i];
00336 }
00337 bFirstIter = false;
00338 }
00339
00340 *PolValue = vals[startind];
00341
00342 SBPL_PRINTF("done\n");
00343 }
00344
00345
00346
00347 void get_bresenham_parameters(int p1x, int p1y, int p2x, int p2y, bresenham_param_t *params)
00348 {
00349 params->UsingYIndex = 0;
00350
00351 if (fabs((double)(p2y-p1y)/(double)(p2x-p1x)) > 1)
00352 (params->UsingYIndex)++;
00353
00354 if (params->UsingYIndex)
00355 {
00356 params->Y1=p1x;
00357 params->X1=p1y;
00358 params->Y2=p2x;
00359 params->X2=p2y;
00360 }
00361 else
00362 {
00363 params->X1=p1x;
00364 params->Y1=p1y;
00365 params->X2=p2x;
00366 params->Y2=p2y;
00367 }
00368
00369 if ((p2x - p1x) * (p2y - p1y) < 0)
00370 {
00371 params->Flipped = 1;
00372 params->Y1 = -params->Y1;
00373 params->Y2 = -params->Y2;
00374 }
00375 else
00376 params->Flipped = 0;
00377
00378 if (params->X2 > params->X1)
00379 params->Increment = 1;
00380 else
00381 params->Increment = -1;
00382
00383 params->DeltaX=params->X2-params->X1;
00384 params->DeltaY=params->Y2-params->Y1;
00385
00386 params->IncrE=2*params->DeltaY*params->Increment;
00387 params->IncrNE=2*(params->DeltaY-params->DeltaX)*params->Increment;
00388 params->DTerm=(2*params->DeltaY-params->DeltaX)*params->Increment;
00389
00390 params->XIndex = params->X1;
00391 params->YIndex = params->Y1;
00392 }
00393
00394 void get_current_point(bresenham_param_t *params, int *x, int *y)
00395 {
00396 if (params->UsingYIndex)
00397 {
00398 *y = params->XIndex;
00399 *x = params->YIndex;
00400 if (params->Flipped)
00401 *x = -*x;
00402 }
00403 else
00404 {
00405 *x = params->XIndex;
00406 *y = params->YIndex;
00407 if (params->Flipped)
00408 *y = -*y;
00409 }
00410 }
00411
00412 int get_next_point(bresenham_param_t *params)
00413 {
00414 if (params->XIndex == params->X2)
00415 {
00416 return 0;
00417 }
00418 params->XIndex += params->Increment;
00419 if (params->DTerm < 0 || (params->Increment < 0 && params->DTerm <= 0))
00420 params->DTerm += params->IncrE;
00421 else
00422 {
00423 params->DTerm += params->IncrNE;
00424 params->YIndex += params->Increment;
00425 }
00426 return 1;
00427 }
00428
00429
00430
00431
00432
00433 double DiscTheta2Cont(int nTheta, int NUMOFANGLEVALS)
00434 {
00435 double thetaBinSize = 2.0*PI_CONST/NUMOFANGLEVALS;
00436 return nTheta*thetaBinSize;
00437 }
00438
00439
00440
00441
00442
00443 int ContTheta2Disc(double fTheta, int NUMOFANGLEVALS)
00444 {
00445
00446 double thetaBinSize = 2.0*PI_CONST/NUMOFANGLEVALS;
00447 return (int)(normalizeAngle(fTheta+thetaBinSize/2.0)/(2.0*PI_CONST)*(NUMOFANGLEVALS));
00448
00449 }
00450
00451
00452
00453
00454
00455
00456
00457 double normalizeAngle(double angle)
00458 {
00459 double retangle = angle;
00460
00461
00462 if(fabs(retangle) > 2*PI_CONST)
00463 retangle = retangle - ((int)(retangle/(2*PI_CONST)))*2*PI_CONST;
00464
00465
00466 if(retangle < 0)
00467 retangle += 2*PI_CONST;
00468
00469 if(retangle < 0 || retangle > 2*PI_CONST)
00470 {
00471 SBPL_ERROR("ERROR: after normalization of angle=%f we get angle=%f\n", angle, retangle);
00472 }
00473
00474 return retangle;
00475 }
00476
00477
00478
00479
00480
00481
00482
00483
00484 bool IsInsideFootprint(sbpl_2Dpt_t pt, vector<sbpl_2Dpt_t>* bounding_polygon){
00485
00486 int counter = 0;
00487 int i;
00488 double xinters;
00489 sbpl_2Dpt_t p1;
00490 sbpl_2Dpt_t p2;
00491 int N = bounding_polygon->size();
00492
00493 p1 = bounding_polygon->at(0);
00494 for (i=1;i<=N;i++) {
00495 p2 = bounding_polygon->at(i % N);
00496 if (pt.y > __min(p1.y,p2.y)) {
00497 if (pt.y <= __max(p1.y,p2.y)) {
00498 if (pt.x <= __max(p1.x,p2.x)) {
00499 if (p1.y != p2.y) {
00500 xinters = (pt.y-p1.y)*(p2.x-p1.x)/(p2.y-p1.y)+p1.x;
00501 if (p1.x == p2.x || pt.x <= xinters)
00502 counter++;
00503 }
00504 }
00505 }
00506 }
00507 p1 = p2;
00508 }
00509
00510 if (counter % 2 == 0)
00511 return false;
00512 else
00513 return true;
00514 #if DEBUG
00515
00516 #endif
00517
00518
00519 }
00520
00521
00522 double computeMinUnsignedAngleDiff(double angle1, double angle2)
00523 {
00524
00525 angle1 = normalizeAngle(angle1);
00526 angle2 = normalizeAngle(angle2);
00527
00528 double anglediff = fabs(angle1-angle2);
00529
00530
00531 if(anglediff > PI_CONST){
00532 anglediff = fabs(anglediff - 2*PI_CONST);
00533 }
00534
00535 return anglediff;
00536 }
00537
00538
00539
00540
00541
00542
00543 void computeDistancestoNonfreeAreas(unsigned char** Grid2D, int width_x, int height_y, unsigned char obsthresh, float** disttoObs_incells,
00544 float** disttoNonfree_incells)
00545 {
00546 int x,y,nbrx,nbry;
00547 float mindisttoObs, mindisttoNonfree;
00548 float maxDist = (float)(__min(width_x, height_y));
00549 float disttoObs, disttoNonfree;
00550 int dir;
00551 const int NUMOF2DQUASIDIRS = 4;
00552
00553
00554
00555 int dxdownlefttoright_[NUMOF2DQUASIDIRS];
00556 int dydownlefttoright_[NUMOF2DQUASIDIRS];
00557 int dxdownrighttoleft_[NUMOF2DQUASIDIRS];
00558 int dydownrighttoleft_[NUMOF2DQUASIDIRS];
00559
00560
00561 int dxuprighttoleft_[NUMOF2DQUASIDIRS];
00562 int dyuprighttoleft_[NUMOF2DQUASIDIRS];
00563 int dxuplefttoright_[NUMOF2DQUASIDIRS];
00564 int dyuplefttoright_[NUMOF2DQUASIDIRS];
00565
00566
00567 float distdownlefttoright_[NUMOF2DQUASIDIRS];
00568 float distdownrighttoleft_[NUMOF2DQUASIDIRS];
00569 float distuprighttoleft_[NUMOF2DQUASIDIRS];
00570 float distuplefttoright_[NUMOF2DQUASIDIRS];
00571
00572
00573
00574
00575
00576
00577
00578 dxdownlefttoright_[0] = -1; dydownlefttoright_[0] = -1;
00579 dxdownlefttoright_[1] = -1; dydownlefttoright_[1] = 0;
00580 dxdownlefttoright_[2] = -1; dydownlefttoright_[2] = 1;
00581 dxdownlefttoright_[3] = 0; dydownlefttoright_[3] = -1;
00582
00583
00584
00585
00586
00587
00588 dxdownrighttoleft_[0] = -1; dydownrighttoleft_[0] = -1;
00589 dxdownrighttoleft_[1] = -1; dydownrighttoleft_[1] = 0;
00590 dxdownrighttoleft_[2] = -1; dydownrighttoleft_[2] = 1;
00591 dxdownrighttoleft_[3] = 0; dydownrighttoleft_[3] = 1;
00592
00593
00594
00595
00596
00597
00598 dxuprighttoleft_[0] = 1; dyuprighttoleft_[0] = -1;
00599 dxuprighttoleft_[1] = 1; dyuprighttoleft_[1] = 0;
00600 dxuprighttoleft_[2] = 1; dyuprighttoleft_[2] = 1;
00601 dxuprighttoleft_[3] = 0; dyuprighttoleft_[3] = 1;
00602
00603
00604
00605
00606
00607
00608 dxuplefttoright_[0] = 1; dyuplefttoright_[0] = -1;
00609 dxuplefttoright_[1] = 1; dyuplefttoright_[1] = 0;
00610 dxuplefttoright_[2] = 1; dyuplefttoright_[2] = 1;
00611 dxuplefttoright_[3] = 0; dyuplefttoright_[3] = -1;
00612
00613
00614 distdownlefttoright_[0] = (float)1.414;
00615 distdownlefttoright_[1] = (float)1.0;
00616 distdownlefttoright_[2] = (float)1.414;
00617 distdownlefttoright_[3] = (float)1.0;
00618
00619 distdownrighttoleft_[0] = (float)1.414;
00620 distdownrighttoleft_[1] = (float)1.0;
00621 distdownrighttoleft_[2] = (float)1.414;
00622 distdownrighttoleft_[3] = (float)1.0;
00623
00624 distuprighttoleft_[0] = (float)1.414;
00625 distuprighttoleft_[1] = (float)1.0;
00626 distuprighttoleft_[2] = (float)1.414;
00627 distuprighttoleft_[3] = (float)1.0;
00628
00629 distuplefttoright_[0] = (float)1.414;
00630 distuplefttoright_[1] = (float)1.0;
00631 distuplefttoright_[2] = (float)1.414;
00632 distuplefttoright_[3] = (float)1.0;
00633
00634
00635
00636
00637
00638
00639 for(x = 0; x < width_x; x++)
00640 {
00641
00642 if (x%2 == 0) {
00643
00644 for(y = 0; y < height_y; y++)
00645 {
00646
00647 mindisttoObs = maxDist;
00648 mindisttoNonfree = maxDist;
00649
00650
00651 if (Grid2D[x][y] >= obsthresh){
00652 disttoObs_incells[x][y] = 0;
00653 disttoNonfree_incells[x][y] = 0;
00654 continue;
00655 }
00656
00657 if(Grid2D[x][y] > 0){
00658 mindisttoNonfree = 0;
00659 }
00660
00661
00662 for(dir = 0; dir < NUMOF2DQUASIDIRS; dir++){
00663 nbrx = x + dxdownlefttoright_[dir];
00664 nbry = y + dydownlefttoright_[dir];
00665
00666
00667
00668
00669 if(nbrx < 0 || nbrx >= width_x || nbry < 0 || nbry >= height_y){
00670 disttoObs = distdownlefttoright_[dir];
00671 disttoNonfree = disttoObs;
00672 }
00673 else
00674 {
00675 disttoObs = distdownlefttoright_[dir] + disttoObs_incells[nbrx][nbry];
00676 disttoNonfree = distdownlefttoright_[dir] + disttoNonfree_incells[nbrx][nbry];
00677 }
00678
00679 if (disttoObs < mindisttoObs)
00680 mindisttoObs = disttoObs;
00681 if (disttoNonfree < mindisttoNonfree)
00682 mindisttoNonfree = disttoNonfree;
00683 }
00684
00685 disttoObs_incells[x][y] = mindisttoObs;
00686 disttoNonfree_incells[x][y] = mindisttoNonfree;
00687 }
00688
00689 } else {
00690
00691
00692 for(y = height_y-1; y >= 0; y--)
00693 {
00694
00695 mindisttoObs = maxDist;
00696 mindisttoNonfree = maxDist;
00697
00698
00699 if (Grid2D[x][y] >= obsthresh){
00700 disttoObs_incells[x][y] = 0;
00701 disttoNonfree_incells[x][y] = 0;
00702 continue;
00703 }
00704
00705 if(Grid2D[x][y] > 0){
00706 mindisttoNonfree = 0;
00707 }
00708
00709
00710
00711 for(dir = 0; dir < NUMOF2DQUASIDIRS; dir++)
00712 {
00713 nbrx = x + dxdownrighttoleft_[dir];
00714 nbry = y + dydownrighttoleft_[dir];
00715
00716
00717
00718
00719 if(nbrx < 0 || nbrx >= width_x || nbry < 0 || nbry >= height_y){
00720 disttoObs = distdownrighttoleft_[dir];
00721 disttoNonfree = disttoObs;
00722 } else {
00723 disttoObs = distdownrighttoleft_[dir] + disttoObs_incells[nbrx][nbry];
00724 disttoNonfree = distdownrighttoleft_[dir] + disttoNonfree_incells[nbrx][nbry];
00725 }
00726
00727 if (disttoObs < mindisttoObs)
00728 mindisttoObs = disttoObs;
00729 if (disttoNonfree < mindisttoNonfree)
00730 mindisttoNonfree = disttoNonfree;
00731 }
00732
00733 disttoObs_incells[x][y] = mindisttoObs;
00734 disttoNonfree_incells[x][y] = mindisttoNonfree;
00735 }
00736
00737 }
00738 }
00739
00740
00741 for(x = width_x-1; x >= 0; x--)
00742 {
00743
00744
00745 if (x%2 == 0) {
00746
00747 for(y = height_y-1; y >= 0; y--)
00748 {
00749
00750
00751 mindisttoObs = disttoObs_incells[x][y];
00752 mindisttoNonfree = disttoNonfree_incells[x][y];
00753
00754
00755 for(dir = 0; dir < NUMOF2DQUASIDIRS; dir++)
00756 {
00757 nbrx = x + dxuprighttoleft_[dir];
00758 nbry = y + dyuprighttoleft_[dir];
00759
00760
00761
00762
00763 if(nbrx < 0 || nbrx >= width_x || nbry < 0 || nbry >= height_y){
00764 disttoObs = distuprighttoleft_[dir];
00765 disttoNonfree = disttoObs;
00766 } else {
00767 disttoObs = distuprighttoleft_[dir] + disttoObs_incells[nbrx][nbry];
00768 disttoNonfree = distuprighttoleft_[dir] + disttoNonfree_incells[nbrx][nbry];
00769 }
00770
00771 if (disttoObs < mindisttoObs)
00772 mindisttoObs = disttoObs;
00773 if (disttoNonfree < mindisttoNonfree)
00774 mindisttoNonfree = disttoNonfree;
00775 }
00776
00777 disttoObs_incells[x][y] = mindisttoObs;
00778 disttoNonfree_incells[x][y] = mindisttoNonfree;
00779 }
00780 } else {
00781
00782
00783 for(y = 0; y< height_y; y++)
00784 {
00785
00786 mindisttoObs = disttoObs_incells[x][y];
00787 mindisttoNonfree = disttoNonfree_incells[x][y];
00788
00789
00790 for(dir = 0; dir < NUMOF2DQUASIDIRS; dir++)
00791 {
00792 nbrx = x + dxuplefttoright_[dir];
00793 nbry = y + dyuplefttoright_[dir];
00794
00795
00796
00797
00798 if(nbrx < 0 || nbrx >= width_x || nbry < 0 || nbry >= height_y){
00799 disttoObs = distuplefttoright_[dir];
00800 disttoNonfree = disttoObs;
00801 } else {
00802 disttoObs = distuplefttoright_[dir] + disttoObs_incells[nbrx][nbry];
00803 disttoNonfree = distuplefttoright_[dir] + disttoNonfree_incells[nbrx][nbry];
00804 }
00805
00806 if (disttoObs < mindisttoObs)
00807 mindisttoObs = disttoObs;
00808 if (disttoNonfree < mindisttoNonfree)
00809 mindisttoNonfree = disttoNonfree;
00810 }
00811
00812 disttoObs_incells[x][y] = mindisttoObs;
00813 disttoNonfree_incells[x][y] = mindisttoNonfree;
00814 }
00815 }
00816 }
00817 }