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
00035
00036
00037
00038 SBPL2DGridSearch::SBPL2DGridSearch(int width_x, int height_y, float cellsize_m)
00039 {
00040 iteration_ = 0;
00041 searchStates2D_ = NULL;
00042
00043 width_ = width_x;
00044 height_ = height_y;
00045 cellSize_m_ = cellsize_m;
00046
00047 startX_ = -1;
00048 startY_ = -1;
00049 goalX_ = -1;
00050 goalY_ = -1;
00051
00052 largestcomputedoptf_ = 0;
00053
00054
00055 computedxy();
00056
00057 term_condition_usedlast = SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS;
00058
00059
00060 OPEN2D_ = new CIntHeap(width_x*height_y);
00061 if(!createSearchStates2D())
00062 {
00063 SBPL_ERROR("ERROR: failed to create searchstatespace2D\n");
00064 throw new SBPL_Exception();
00065 }
00066
00067
00068 OPEN2DBLIST_ = NULL;
00069 OPENtype_ = SBPL_2DGRIDSEARCH_OPENTYPE_HEAP;
00070
00071 }
00072
00073 bool SBPL2DGridSearch::setOPENdatastructure(SBPL_2DGRIDSEARCH_OPENTYPE OPENtype)
00074 {
00075 OPENtype_ = OPENtype;
00076
00077 switch(OPENtype_)
00078 {
00079 case SBPL_2DGRIDSEARCH_OPENTYPE_HEAP:
00080
00081 break;
00082 case SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS:
00083 SBPL_PRINTF("setting OPEN2D data structure to sliding buckets\n");
00084 if(OPEN2DBLIST_ == NULL)
00085 {
00086
00087
00088 int maxdistance = 0;
00089 for(int dind = 0; dind < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dind++)
00090 {
00091 maxdistance = __max(maxdistance, dxy_distance_mm_[dind]);
00092 }
00093 int bucketsize = __max(1000, this->width_ + this->height_);
00094 int numofbuckets = 255*maxdistance;
00095 SBPL_PRINTF("creating sliding bucket-based OPEN2D %d buckets, each bucket of size %d ...", numofbuckets, bucketsize);
00096 OPEN2DBLIST_ = new CSlidingBucket(numofbuckets, bucketsize);
00097 SBPL_PRINTF("done\n");
00098 }
00099
00100 if(OPEN2D_ != NULL){
00101 OPEN2D_->makeemptyheap();
00102 delete OPEN2D_;
00103 OPEN2D_ = NULL;
00104 }
00105
00106 break;
00107 default:
00108 SBPL_ERROR("ERROR: unknown data structure type = %d for OPEN2D\n", OPENtype_);
00109 throw new SBPL_Exception();
00110 };
00111
00112 return true;
00113 }
00114
00115
00116 bool SBPL2DGridSearch::createSearchStates2D(void)
00117 {
00118 int x,y;
00119
00120 if(searchStates2D_ != NULL){
00121 SBPL_ERROR("ERROR: We already have a non-NULL search states array\n");
00122 return false;
00123 }
00124
00125 searchStates2D_ = new SBPL_2DGridSearchState* [width_];
00126 for(x = 0; x < width_; x++)
00127 {
00128 searchStates2D_[x] = new SBPL_2DGridSearchState[height_];
00129 for(y = 0; y < height_; y++)
00130 {
00131 searchStates2D_[x][y].iterationaccessed = iteration_;
00132 searchStates2D_[x][y].x = x;
00133 searchStates2D_[x][y].y = y;
00134 initializeSearchState2D(&searchStates2D_[x][y]);
00135 }
00136 }
00137 return true;
00138 }
00139
00140 inline void SBPL2DGridSearch::initializeSearchState2D(SBPL_2DGridSearchState* state2D)
00141 {
00142 state2D->g = INFINITECOST;
00143 state2D->heapindex = 0;
00144 state2D->iterationaccessed = iteration_;
00145 }
00146
00147
00148 void SBPL2DGridSearch::destroy()
00149 {
00150
00151
00152 if(OPEN2D_ != NULL){
00153 OPEN2D_->makeemptyheap();
00154 delete OPEN2D_;
00155 OPEN2D_ = NULL;
00156 }
00157
00158
00159 if(searchStates2D_ != NULL){
00160 for(int x = 0; x < width_; x++)
00161 {
00162 delete [] searchStates2D_[x];
00163 }
00164 delete [] searchStates2D_;
00165 searchStates2D_ = NULL;
00166 }
00167
00168 if(OPEN2DBLIST_ != NULL)
00169 {
00170 delete OPEN2DBLIST_;
00171 OPEN2DBLIST_ = NULL;
00172 }
00173 }
00174
00175
00176 void SBPL2DGridSearch::computedxy()
00177 {
00178
00179
00180 dx_[0] = 1; dy_[0] = 1; dx0intersects_[0] = -1; dy0intersects_[0] = -1;
00181 dx_[1] = 1; dy_[1] = 0; dx0intersects_[1] = -1; dy0intersects_[1] = -1;
00182 dx_[2] = 1; dy_[2] = -1; dx0intersects_[2] = -1; dy0intersects_[2] = -1;
00183 dx_[3] = 0; dy_[3] = 1; dx0intersects_[3] = -1; dy0intersects_[3] = -1;
00184 dx_[4] = 0; dy_[4] = -1; dx0intersects_[4] = -1; dy0intersects_[4] = -1;
00185 dx_[5] = -1; dy_[5] = 1; dx0intersects_[5] = -1; dy0intersects_[5] = -1;
00186 dx_[6] = -1; dy_[6] = 0; dx0intersects_[6] = -1; dy0intersects_[6] = -1;
00187 dx_[7] = -1; dy_[7] = -1; dx0intersects_[7] = -1; dy0intersects_[7] = -1;
00188
00189
00190
00191 #if SBPL_2DGRIDSEARCH_NUMOF2DDIRS == 16
00192 dx_[8] = 2; dy_[8] = 1; dx0intersects_[8] = 1; dy0intersects_[8] = 0; dx1intersects_[8] = 1; dy1intersects_[8] = 1;
00193 dx_[9] = 1; dy_[9] = 2; dx0intersects_[9] = 0; dy0intersects_[9] = 1; dx1intersects_[9] = 1; dy1intersects_[9] = 1;
00194 dx_[10] = -1; dy_[10] = 2; dx0intersects_[10] = 0; dy0intersects_[10] = 1; dx1intersects_[10] = -1; dy1intersects_[10] = 1;
00195 dx_[11] = -2; dy_[11] = 1; dx0intersects_[11] = -1; dy0intersects_[11] = 0; dx1intersects_[11] = -1; dy1intersects_[11] = 1;
00196 dx_[12] = -2; dy_[12] = -1; dx0intersects_[12] = -1; dy0intersects_[12] = 0; dx1intersects_[12] = -1; dy1intersects_[12] = -1;
00197 dx_[13] = -1; dy_[13] = -2; dx0intersects_[13] = 0; dy0intersects_[13] = -1; dx1intersects_[13] = -1; dy1intersects_[13] = -1;
00198 dx_[14] = 1; dy_[14] = -2; dx0intersects_[14] = 0; dy0intersects_[14] = -1; dx1intersects_[14] = 1; dy1intersects_[14] = -1;
00199 dx_[15] = 2; dy_[15] = -1; dx0intersects_[15] = 1; dy0intersects_[15] = 0; dx1intersects_[15] = 1; dy1intersects_[15] = -1;
00200 #endif
00201
00202
00203 for(int dind = 0; dind < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dind++)
00204 {
00205
00206 if(dx_[dind] != 0 && dy_[dind] != 0){
00207 if(dind <= 7)
00208 dxy_distance_mm_[dind] = (int)(cellSize_m_*1414);
00209 else
00210 dxy_distance_mm_[dind] = (int)(cellSize_m_*2236);
00211 }
00212 else
00213 dxy_distance_mm_[dind] = (int)(cellSize_m_*1000);
00214 }
00215 }
00216
00217
00218
00219
00220
00221 void SBPL2DGridSearch::printvalues()
00222 {
00223
00224
00225
00226 }
00227
00228
00229
00230
00231 bool SBPL2DGridSearch::search(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, int goaly_c,
00232 SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition)
00233 {
00234
00235 switch(OPENtype_)
00236 {
00237 case SBPL_2DGRIDSEARCH_OPENTYPE_HEAP:
00238 return SBPL2DGridSearch::search_withheap(Grid2D, obsthresh, startx_c, starty_c, goalx_c, goaly_c,
00239 termination_condition);
00240 break;
00241 case SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS:
00242 return SBPL2DGridSearch::search_withslidingbuckets(Grid2D, obsthresh, startx_c, starty_c, goalx_c, goaly_c, termination_condition);
00243 break;
00244 default:
00245 SBPL_ERROR("ERROR: unknown data structure type = %d for OPEN2D\n", OPENtype_);
00246 throw new SBPL_Exception();
00247 };
00248 return false;
00249 }
00250
00251
00252
00253 bool SBPL2DGridSearch::search_withheap(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, int goaly_c,
00254 SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition)
00255 {
00256
00257 SBPL_2DGridSearchState *searchExpState = NULL;
00258 SBPL_2DGridSearchState *searchPredState = NULL;
00259 int numofExpands = 0;
00260 int key;
00261
00262
00263 clock_t starttime = clock();
00264
00265
00266 iteration_++;
00267
00268
00269 startX_ = startx_c;
00270 startY_ = starty_c;
00271 goalX_ = goalx_c;
00272 goalY_ = goaly_c;
00273
00274
00275 OPEN2D_->makeemptyheap();
00276
00277
00278 term_condition_usedlast = termination_condition;
00279
00280
00281 if(!withinMap(startx_c, starty_c) || !withinMap(goalx_c, goaly_c))
00282 {
00283 SBPL_ERROR("ERROR: grid2Dsearch is called on invalid start (%d %d) or goal(%d %d)\n", startx_c, starty_c, goalx_c, goaly_c);
00284 return false;
00285 }
00286
00287
00288 searchExpState = &searchStates2D_[startX_][startY_];
00289 initializeSearchState2D(searchExpState);
00290 initializeSearchState2D(&searchStates2D_[goalx_c][goaly_c]);
00291 SBPL_2DGridSearchState* search2DGoalState = &searchStates2D_[goalx_c][goaly_c];
00292
00293
00294 searchExpState->g = 0;
00295 key = searchExpState->g;
00296 if(termination_condition == SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND)
00297 key = key + SBPL_2DGRIDSEARCH_HEUR2D(startX_,startY_);
00298
00299 OPEN2D_->insertheap(searchExpState, key);
00300
00301
00302
00303 float term_factor = 0.0;
00304 switch(termination_condition)
00305 {
00306 case SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND:
00307 term_factor = 1;
00308 break;
00309 case SBPL_2DGRIDSEARCH_TERM_CONDITION_20PERCENTOVEROPTPATH:
00310 term_factor = (float)(1.0/1.2);
00311 break;
00312 case SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH:
00313 term_factor = 0.5;
00314 break;
00315 case SBPL_2DGRIDSEARCH_TERM_CONDITION_THREETIMESOPTPATH:
00316 term_factor = (float)(1.0/3.0);
00317 break;
00318 case SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS:
00319 term_factor = 0.0;
00320 break;
00321 default:
00322 SBPL_ERROR("ERROR: incorrect termination factor for grid2Dsearch\n");
00323 term_factor = 0.0;
00324 };
00325
00326 char *pbClosed = (char*)calloc(1, width_*height_);
00327
00328
00329 while(!OPEN2D_->emptyheap() && __min(INFINITECOST, search2DGoalState->g) > term_factor*OPEN2D_->getminkeyheap())
00330 {
00331
00332 searchExpState = (SBPL_2DGridSearchState*)OPEN2D_->deleteminheap();
00333 numofExpands++;
00334
00335 int exp_x = searchExpState->x;
00336 int exp_y = searchExpState->y;
00337
00338
00339 pbClosed[exp_x + width_*exp_y] = 1;
00340
00341
00342 int expcost = Grid2D[exp_x][exp_y];
00343 for(int dir = 0; dir < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dir++)
00344 {
00345 int newx = exp_x + dx_[dir];
00346 int newy = exp_y + dy_[dir];
00347
00348
00349 if(!withinMap(newx, newy))
00350 continue;
00351
00352 if(pbClosed[newx + width_*newy] == 1)
00353 continue;
00354
00355
00356 int mapcost = __max(Grid2D[newx][newy], expcost);
00357
00358 #if SBPL_2DGRIDSEARCH_NUMOF2DDIRS > 8
00359 if(dir > 7){
00360
00361 mapcost = __max(mapcost, Grid2D[exp_x + dx0intersects_[dir]][exp_y + dy0intersects_[dir]]);
00362 mapcost = __max(mapcost, Grid2D[exp_x + dx1intersects_[dir]][exp_y + dy1intersects_[dir]]);
00363 }
00364 #endif
00365
00366 if(mapcost >= obsthresh)
00367 continue;
00368 int cost = (mapcost+1)*dxy_distance_mm_[dir];
00369
00370
00371 searchPredState = &searchStates2D_[newx][newy];
00372
00373
00374 if(searchPredState->iterationaccessed != iteration_ || searchPredState->g > cost + searchExpState->g)
00375 {
00376 searchPredState->iterationaccessed = iteration_;
00377 searchPredState->g = __min(INFINITECOST, cost + searchExpState->g);
00378 key = searchPredState->g;
00379 if(termination_condition == SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND)
00380 key = key + SBPL_2DGRIDSEARCH_HEUR2D(searchPredState->x, searchPredState->y);
00381
00382 if(searchPredState->heapindex == 0)
00383 OPEN2D_->insertheap(searchPredState, key);
00384 else
00385 OPEN2D_->updateheap(searchPredState, key);
00386
00387 }
00388 }
00389 }
00390
00391
00392 if(!OPEN2D_->emptyheap())
00393 largestcomputedoptf_ = OPEN2D_->getminkeyheap();
00394 else
00395 largestcomputedoptf_ = INFINITECOST;
00396
00397
00398 delete [] pbClosed;
00399
00400 SBPL_PRINTF("# of expands during 2dgridsearch=%d time=%d msecs 2Dsolcost_inmm=%d largestoptfval=%d (start=%d %d goal=%d %d)\n",
00401 numofExpands, (int)(((clock()-starttime)/(double)CLOCKS_PER_SEC)*1000), searchStates2D_[goalx_c][goaly_c].g, largestcomputedoptf_,
00402 startx_c, starty_c, goalx_c, goaly_c);
00403
00404 return false;
00405 }
00406
00407
00408
00409
00410
00411 bool SBPL2DGridSearch::search_exp(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, int goaly_c)
00412 {
00413
00414 SBPL_2DGridSearchState *searchExpState = NULL;
00415 SBPL_2DGridSearchState *searchPredState = NULL;
00416 int numofExpands = 0;
00417 CList OPEN2DLIST;
00418
00419
00420 clock_t starttime = clock();
00421
00422
00423 iteration_++;
00424
00425
00426 startX_ = startx_c;
00427 startY_ = starty_c;
00428 goalX_ = goalx_c;
00429 goalY_ = goaly_c;
00430
00431
00432 if(!withinMap(startx_c, starty_c) || !withinMap(goalx_c, goaly_c))
00433 {
00434 SBPL_ERROR("ERROR: grid2Dsearch is called on invalid start (%d %d) or goal(%d %d)\n", startx_c, starty_c, goalx_c, goaly_c);
00435 return false;
00436 }
00437
00438
00439 searchExpState = &searchStates2D_[startX_][startY_];
00440 initializeSearchState2D(searchExpState);
00441
00442
00443
00444 searchExpState->g = 0;
00445 searchExpState->listelem[SBPL_2DSEARCH_OPEN_LIST_ID] = NULL;
00446 OPEN2DLIST.insertinfront(searchExpState, SBPL_2DSEARCH_OPEN_LIST_ID);
00447
00448
00449 while(!OPEN2DLIST.empty())
00450 {
00451
00452 searchExpState = (SBPL_2DGridSearchState*)OPEN2DLIST.getlast();
00453 OPEN2DLIST.remove(searchExpState, SBPL_2DSEARCH_OPEN_LIST_ID);
00454 numofExpands++;
00455
00456 int exp_x = searchExpState->x;
00457 int exp_y = searchExpState->y;
00458
00459
00460 for(int dir = 0; dir < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dir++)
00461 {
00462 int newx = exp_x + dx_[dir];
00463 int newy = exp_y + dy_[dir];
00464
00465
00466 if(!withinMap(newx, newy))
00467 continue;
00468
00469
00470 int mapcost = __max(Grid2D[newx][newy], Grid2D[exp_x][exp_y]);
00471
00472 #if SBPL_2DGRIDSEARCH_NUMOF2DDIRS > 8
00473 if(dir > 7){
00474
00475 mapcost = __max(mapcost, Grid2D[exp_x + dx0intersects_[dir]][exp_y + dy0intersects_[dir]]);
00476 mapcost = __max(mapcost, Grid2D[exp_x + dx1intersects_[dir]][exp_y + dy1intersects_[dir]]);
00477 }
00478 #endif
00479
00480 if(mapcost >= obsthresh)
00481 continue;
00482 int cost = (mapcost+1)*dxy_distance_mm_[dir];
00483
00484
00485 searchPredState = &searchStates2D_[newx][newy];
00486
00487
00488 if(searchPredState->iterationaccessed != iteration_)
00489 searchPredState->listelem[SBPL_2DSEARCH_OPEN_LIST_ID] = NULL;
00490
00491
00492 if(searchPredState->iterationaccessed != iteration_ || searchPredState->g > cost + searchExpState->g)
00493 {
00494 searchPredState->iterationaccessed = iteration_;
00495 searchPredState->g = __min(INFINITECOST, cost + searchExpState->g);
00496
00497 if(searchPredState->g >= INFINITECOST)
00498 {
00499 SBPL_ERROR("ERROR: infinite g\n");
00500 throw new SBPL_Exception();
00501 }
00502
00503
00504 if(searchPredState->listelem[SBPL_2DSEARCH_OPEN_LIST_ID] == NULL)
00505 OPEN2DLIST.insertinfront(searchPredState, SBPL_2DSEARCH_OPEN_LIST_ID);
00506
00507 }
00508 }
00509 }
00510
00511
00512 largestcomputedoptf_ = INFINITECOST;
00513
00514
00515 SBPL_PRINTF("# of expands during 2dgridsearch=%d time=%d msecs 2Dsolcost_inmm=%d largestoptfval=%d (start=%d %d goal=%d %d)\n",
00516 numofExpands, (int)(((clock()-starttime)/(double)CLOCKS_PER_SEC)*1000), searchStates2D_[goalx_c][goaly_c].g, largestcomputedoptf_,
00517 startx_c, starty_c, goalx_c, goaly_c);
00518
00519 return false;
00520 }
00521
00522
00523
00524
00525 bool SBPL2DGridSearch::search_withbuckets(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, int goaly_c)
00526 {
00527
00528 SBPL_2DGridSearchState *searchExpState = NULL;
00529 SBPL_2DGridSearchState *searchPredState = NULL;
00530 int numofExpands = 0;
00531
00532
00533 clock_t starttime = clock();
00534
00535
00536 int max_bucketed_priority = (int)(0.1*obsthresh*dxy_distance_mm_[0]*__max(this->width_, this->height_));
00537 SBPL_PRINTF("bucket-based OPEN2D has up to %d bucketed priorities, the rest will be unsorted\n", max_bucketed_priority);
00538 CBucket OPEN2DBLIST(0, max_bucketed_priority);
00539
00540 SBPL_PRINTF("OPEN2D allocation time=%d msecs\n", (int)(((clock()-starttime)/(double)CLOCKS_PER_SEC)*1000));
00541
00542
00543 iteration_++;
00544
00545
00546 startX_ = startx_c;
00547 startY_ = starty_c;
00548 goalX_ = goalx_c;
00549 goalY_ = goaly_c;
00550
00551
00552 if(!withinMap(startx_c, starty_c) || !withinMap(goalx_c, goaly_c))
00553 {
00554 SBPL_ERROR("ERROR: grid2Dsearch is called on invalid start (%d %d) or goal(%d %d)\n", startx_c, starty_c, goalx_c, goaly_c);
00555 return false;
00556 }
00557
00558
00559 searchExpState = &searchStates2D_[startX_][startY_];
00560 initializeSearchState2D(searchExpState);
00561
00562
00563
00564 searchExpState->g = 0;
00565 searchExpState->heapindex = -1;
00566 OPEN2DBLIST.insert(searchExpState, searchExpState->g);
00567
00568
00569 while(!OPEN2DBLIST.empty())
00570 {
00571
00572 searchExpState = (SBPL_2DGridSearchState*)OPEN2DBLIST.popminelement();
00573 numofExpands++;
00574
00575 int exp_x = searchExpState->x;
00576 int exp_y = searchExpState->y;
00577
00578
00579 for(int dir = 0; dir < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dir++)
00580 {
00581 int newx = exp_x + dx_[dir];
00582 int newy = exp_y + dy_[dir];
00583
00584
00585 if(!withinMap(newx, newy))
00586 continue;
00587
00588
00589 int mapcost = __max(Grid2D[newx][newy], Grid2D[exp_x][exp_y]);
00590
00591 #if SBPL_2DGRIDSEARCH_NUMOF2DDIRS > 8
00592 if(dir > 7){
00593
00594 mapcost = __max(mapcost, Grid2D[exp_x + dx0intersects_[dir]][exp_y + dy0intersects_[dir]]);
00595 mapcost = __max(mapcost, Grid2D[exp_x + dx1intersects_[dir]][exp_y + dy1intersects_[dir]]);
00596 }
00597 #endif
00598
00599 if(mapcost >= obsthresh)
00600 continue;
00601 int cost = (mapcost+1)*dxy_distance_mm_[dir];
00602
00603
00604 searchPredState = &searchStates2D_[newx][newy];
00605
00606
00607 if(searchPredState->iterationaccessed != iteration_)
00608 searchPredState->heapindex = -1;
00609
00610
00611 if(searchPredState->iterationaccessed != iteration_ || searchPredState->g > cost + searchExpState->g)
00612 {
00613 int oldstatepriority = searchPredState->g;
00614 searchPredState->iterationaccessed = iteration_;
00615 searchPredState->g = __min(INFINITECOST, cost + searchExpState->g);
00616
00617 if(searchPredState->g >= INFINITECOST)
00618 {
00619 SBPL_ERROR("ERROR: infinite g\n");
00620 throw new SBPL_Exception();
00621 }
00622
00623
00624 if(searchPredState->heapindex != -1)
00625 OPEN2DBLIST.remove(searchPredState, oldstatepriority);
00626 OPEN2DBLIST.insert(searchPredState, searchPredState->g);
00627 }
00628 }
00629 }
00630
00631
00632 if(!OPEN2DBLIST.empty())
00633 largestcomputedoptf_ = OPEN2DBLIST.getminpriority();
00634 else
00635 largestcomputedoptf_ = INFINITECOST;
00636
00637
00638
00639 SBPL_PRINTF("# of expands during 2dgridsearch=%d time=%d msecs 2Dsolcost_inmm=%d largestoptfval=%d bucketassortedarraymaxsize=%d (start=%d %d goal=%d %d)\n",
00640 numofExpands, (int)(((clock()-starttime)/(double)CLOCKS_PER_SEC)*1000), searchStates2D_[goalx_c][goaly_c].g, largestcomputedoptf_,
00641 OPEN2DBLIST.maxassortedpriorityVsize,
00642 startx_c, starty_c, goalx_c, goaly_c);
00643
00644 return false;
00645 }
00646
00647
00648
00649
00650 bool SBPL2DGridSearch::search_withslidingbuckets(unsigned char** Grid2D, unsigned char obsthresh, int startx_c, int starty_c, int goalx_c, int goaly_c,
00651 SBPL_2DGRIDSEARCH_TERM_CONDITION termination_condition)
00652 {
00653
00654 SBPL_2DGridSearchState *searchExpState = NULL;
00655 SBPL_2DGridSearchState *searchPredState = NULL;
00656 int numofExpands = 0;
00657
00658 #if DEBUG
00659 #ifndef ROS
00660 const char* 2dgriddebug = "2dgriddebug.txt";
00661 #endif
00662 FILE* f2Dsearch = SBPL_FOPEN(2dgriddebug, "w");
00663 #endif
00664
00665
00666 iteration_++;
00667
00668
00669 startX_ = startx_c;
00670 startY_ = starty_c;
00671 goalX_ = goalx_c;
00672 goalY_ = goaly_c;
00673
00674
00675 if(!withinMap(startx_c, starty_c) || !withinMap(goalx_c, goaly_c))
00676 {
00677 SBPL_ERROR("ERROR: grid2Dsearch is called on invalid start (%d %d) or goal(%d %d)\n", startx_c, starty_c, goalx_c, goaly_c);
00678 #if DEBUG
00679 SBPL_FCLOSE(f2Dsearch);
00680 #endif
00681 return false;
00682 }
00683
00684
00685 OPEN2DBLIST_->reset();
00686
00687
00688 term_condition_usedlast = termination_condition;
00689
00690
00691 searchExpState = &searchStates2D_[startX_][startY_];
00692 initializeSearchState2D(searchExpState);
00693 initializeSearchState2D(&searchStates2D_[goalx_c][goaly_c]);
00694 SBPL_2DGridSearchState* search2DGoalState = &searchStates2D_[goalx_c][goaly_c];
00695
00696
00697 searchExpState->g = 0;
00698 OPEN2DBLIST_->insert(searchExpState, searchExpState->g);
00699
00700
00701 float term_factor = 0.0;
00702 switch(termination_condition)
00703 {
00704 case SBPL_2DGRIDSEARCH_TERM_CONDITION_OPTPATHFOUND:
00705 term_factor = 1;
00706 break;
00707 case SBPL_2DGRIDSEARCH_TERM_CONDITION_20PERCENTOVEROPTPATH:
00708 term_factor = (float)(1.0/1.2);
00709 break;
00710 case SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH:
00711 term_factor = 0.5;
00712 break;
00713 case SBPL_2DGRIDSEARCH_TERM_CONDITION_THREETIMESOPTPATH:
00714 term_factor = (float)(1.0/3.0);
00715 break;
00716 case SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS:
00717 term_factor = 0.0;
00718 break;
00719 default:
00720 SBPL_ERROR("ERROR: incorrect termination factor for grid2Dsearch\n");
00721 term_factor = 0.0;
00722 };
00723
00724
00725 clock_t starttime = clock();
00726
00727
00728 char *pbClosed = (char*)calloc(1, width_*height_);
00729
00730
00731 SBPL_PRINTF("2D search with sliding buckets and term_factor=%.3f\n", term_factor);
00732 int prevg = 0;
00733 while(!OPEN2DBLIST_->empty() && search2DGoalState->g > term_factor*OPEN2DBLIST_->getminkey())
00734 {
00735
00736 #if DEBUG
00737 SBPL_FPRINTF(f2Dsearch, "currentminelement_priority before pop=%d\n", OPEN2DBLIST_->getminkey());
00738 #endif
00739
00740
00741 searchExpState = (SBPL_2DGridSearchState*)OPEN2DBLIST_->popminelement();
00742
00743 if(searchExpState->g > OPEN2DBLIST_->getminkey()){
00744 SBPL_ERROR("ERROR: g=%d for state %d %d but minpriority=%d (prevg=%d)\n", searchExpState->g,
00745 searchExpState->x, searchExpState->y, OPEN2DBLIST_->getminkey(), prevg);
00746 }
00747 prevg = searchExpState->g;
00748
00749 int exp_x = searchExpState->x;
00750 int exp_y = searchExpState->y;
00751
00752
00753 if(pbClosed[exp_x + width_*exp_y] == 1)
00754 continue;
00755 pbClosed[exp_x + width_*exp_y] = 1;
00756
00757 #if DEBUG
00758 SBPL_FPRINTF(f2Dsearch, "expanding state <%d %d> with g=%d (currentminelement_priority=%d, currentfirstbucket_bindex=%d, currentfirstbucket_priority=%d)\n",
00759 searchExpState->x, searchExpState->y, searchExpState->g, OPEN2DBLIST_->getminkey(),
00760 OPEN2DBLIST_->currentfirstbucket_bindex, OPEN2DBLIST_->currentfirstbucket_priority);
00761 #endif
00762
00763
00764 numofExpands++;
00765
00766
00767 int expcost = Grid2D[exp_x][exp_y];
00768 for(int dir = 0; dir < SBPL_2DGRIDSEARCH_NUMOF2DDIRS; dir++)
00769 {
00770 int newx = exp_x + dx_[dir];
00771 int newy = exp_y + dy_[dir];
00772
00773
00774 if(!withinMap(newx, newy))
00775 continue;
00776
00777 if(pbClosed[newx + width_*newy] == 1)
00778 continue;
00779
00780
00781 int mapcost = __max(Grid2D[newx][newy], expcost);
00782
00783 #if SBPL_2DGRIDSEARCH_NUMOF2DDIRS > 8
00784 if(dir > 7){
00785
00786 mapcost = __max(mapcost, Grid2D[exp_x + dx0intersects_[dir]][exp_y + dy0intersects_[dir]]);
00787 mapcost = __max(mapcost, Grid2D[exp_x + dx1intersects_[dir]][exp_y + dy1intersects_[dir]]);
00788 }
00789 #endif
00790
00791 if(mapcost >= obsthresh)
00792 continue;
00793 int cost = (mapcost+1)*dxy_distance_mm_[dir];
00794
00795
00796 searchPredState = &searchStates2D_[newx][newy];
00797
00798
00799 if(searchPredState->iterationaccessed != iteration_ || searchPredState->g > cost + searchExpState->g)
00800 {
00801 searchPredState->iterationaccessed = iteration_;
00802 searchPredState->g = __min(INFINITECOST, cost + searchExpState->g);
00803
00804 #if DEBUG
00805 SBPL_FPRINTF(f2Dsearch, "inserting state <%d %d> with g=%d\n", searchPredState->x, searchPredState->y, searchPredState->g);
00806 #endif
00807
00808
00809 OPEN2DBLIST_->insert(searchPredState, searchPredState->g);
00810 }
00811 }
00812 }
00813
00814
00815 if(!OPEN2DBLIST_->empty())
00816 largestcomputedoptf_ = ((SBPL_2DGridSearchState*)OPEN2DBLIST_->getminelement())->g;
00817 else
00818 largestcomputedoptf_ = INFINITECOST;
00819
00820 delete [] pbClosed;
00821
00822
00823 SBPL_PRINTF("# of expands during 2dgridsearch=%d time=%d msecs 2Dsolcost_inmm=%d largestoptfval=%d (start=%d %d goal=%d %d)\n",
00824 numofExpands, (int)(((clock()-starttime)/(double)CLOCKS_PER_SEC)*1000), searchStates2D_[goalx_c][goaly_c].g, largestcomputedoptf_,
00825 startx_c, starty_c, goalx_c, goaly_c);
00826
00827 #if DEBUG
00828 SBPL_FCLOSE(f2Dsearch);
00829 #endif
00830 return false;
00831 }
00832
00833
00834