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 #include <sbpl_dynamic_planner/sipp.h>
00034 #include <algorithm>
00035
00036 #define DRAW_MAP 0
00037
00038
00039 #define DEFAULT_TEMPORAL_PADDING 1 //experiments
00040
00041
00042 #if TIME_DEBUG
00043 static clock_t time3_addallout = 0;
00044 static clock_t time_gethash = 0;
00045 static clock_t time_createhash = 0;
00046 static clock_t time_getsuccs = 0;
00047 #endif
00048
00049 static long int checks = 0;
00050
00051
00052
00053 EnvSIPPLattice::EnvSIPPLattice()
00054 {
00055 SBPL_PRINTF("u1\n");
00056 envSIPPLatCfg.obsthresh = ENVSIPPLAT_DEFAULTOBSTHRESH;
00057 envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh = ENVSIPPLAT_DEFAULTDYNOBSTHRESH;
00058 envSIPPLatCfg.cost_inscribed_thresh = envSIPPLatCfg.obsthresh;
00059 envSIPPLatCfg.cost_possibly_circumscribed_thresh = -1;
00060
00061 grid2Dsearchfromstart = NULL;
00062 grid2Dsearchfromgoal = NULL;
00063 bNeedtoRecomputeStartHeuristics = true;
00064 bNeedtoRecomputeGoalHeuristics = true;
00065 iteration = 0;
00066
00067 envSIPPLat.bInitialized = false;
00068
00069 envSIPPLatCfg.actionwidth = ENVSIPPLAT_DEFAULT_ACTIONWIDTH;
00070 }
00071
00072 EnvSIPPLattice::~EnvSIPPLattice()
00073 {
00074 if(grid2Dsearchfromstart != NULL)
00075 delete grid2Dsearchfromstart;
00076 grid2Dsearchfromstart = NULL;
00077
00078 if(grid2Dsearchfromgoal != NULL)
00079 delete grid2Dsearchfromgoal;
00080 grid2Dsearchfromgoal = NULL;
00081
00082
00083 for (int x = 0; x < envSIPPLatCfg.EnvWidth_c; x++)
00084 delete [] envSIPPLatCfg.Grid2D[x];
00085 delete [] envSIPPLatCfg.Grid2D;
00086
00087 for(int i=0; i<ENVSIPPLAT_THETADIRS; i++)
00088 delete [] envSIPPLatCfg.ActionsV[i];
00089 delete [] envSIPPLatCfg.ActionsV;
00090
00091 for(int i=0; i<ENVSIPPLAT_THETADIRS; i++)
00092 envSIPPLatCfg.PredActionsV[i].clear();
00093 delete [] envSIPPLatCfg.PredActionsV;
00094 }
00095
00096 EnvSIPPLat::~EnvSIPPLat(){
00097 for(unsigned int i=0; i<StateID2CoordTable.size(); i++)
00098 delete StateID2CoordTable[i];
00099 delete [] Coord2StateIDHashTable;
00100 }
00101
00102
00103
00104
00105
00106
00107
00108 static unsigned int inthash(unsigned int key)
00109 {
00110 key += (key << 12);
00111 key ^= (key >> 22);
00112 key += (key << 4);
00113 key ^= (key >> 9);
00114 key += (key << 10);
00115 key ^= (key >> 2);
00116 key += (key << 7);
00117 key ^= (key >> 12);
00118 return key;
00119 }
00120
00121 void EnvSIPPLattice::ReadDynamicObstacles(FILE* fDynObs){
00122 char sTemp[1024], sTemp1[1024];
00123 int iTemp;
00124
00125 SBPL_PRINTF("Reading Dynamic Obstacles...\n");
00126
00127
00128 if(fscanf(fDynObs, "%s", sTemp) != 1){
00129 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00130 throw new SBPL_Exception();
00131 }
00132 strcpy(sTemp1, "NumberOfDynamicObstacles:");
00133 if(strcmp(sTemp1, sTemp) != 0){
00134 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00135 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00136 throw new SBPL_Exception();
00137 }
00138 if(fscanf(fDynObs, "%s", sTemp) != 1){
00139 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00140 throw new SBPL_Exception();
00141 }
00142 int numObs = atoi(sTemp);
00143
00144
00145 for(int i=0; i < numObs; i++){
00146
00147
00148 if(fscanf(fDynObs, "%s", sTemp) != 1){
00149 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00150 throw new SBPL_Exception();
00151 }
00152 strcpy(sTemp1, "DynamicObstacleID:");
00153 if(strcmp(sTemp1, sTemp) != 0){
00154 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00155 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00156 throw new SBPL_Exception();
00157 }
00158 if(fscanf(fDynObs, "%s", sTemp) != 1){
00159 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00160 throw new SBPL_Exception();
00161 }
00162 iTemp = atoi(sTemp);
00163 if(iTemp != i){
00164 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00165 SBPL_PRINTF("Expected %d got %d\n", i, iTemp);
00166 throw new SBPL_Exception();
00167 }
00168 SBPL_DynamicObstacle_t obs;
00169
00170
00171 if(fscanf(fDynObs, "%s", sTemp) != 1){
00172 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00173 throw new SBPL_Exception();
00174 }
00175 strcpy(sTemp1, "ObstacleRadius:");
00176 if(strcmp(sTemp1, sTemp) != 0){
00177 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00178 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00179 throw new SBPL_Exception();
00180 }
00181 if(fscanf(fDynObs, "%s", sTemp) != 1){
00182 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00183 throw new SBPL_Exception();
00184 }
00185 obs.radius = atof(sTemp) + envSIPPLatCfg.robotRadius;
00186
00187
00188 if(fscanf(fDynObs, "%s", sTemp) != 1){
00189 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00190 throw new SBPL_Exception();
00191 }
00192 strcpy(sTemp1, "NumberOfTrajectories:");
00193 if(strcmp(sTemp1, sTemp) != 0){
00194 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00195 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00196 throw new SBPL_Exception();
00197 }
00198 if(fscanf(fDynObs, "%s", sTemp) != 1){
00199 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00200 throw new SBPL_Exception();
00201 }
00202 int numTraj = atoi(sTemp);
00203
00204
00205 double trajProbSum = 0;
00206 for(int j=0; j < numTraj; j++){
00207
00208
00209 if(fscanf(fDynObs, "%s", sTemp) != 1){
00210 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00211 throw new SBPL_Exception();
00212 }
00213 strcpy(sTemp1, "TrajectoryID:");
00214 if(strcmp(sTemp1, sTemp) != 0){
00215 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00216 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00217 throw new SBPL_Exception();
00218 }
00219 if(fscanf(fDynObs, "%s", sTemp) != 1){
00220 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00221 throw new SBPL_Exception();
00222 }
00223 iTemp = atoi(sTemp);
00224 if(iTemp != j){
00225 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00226 SBPL_PRINTF("Expected %d got %d\n", j, iTemp);
00227 throw new SBPL_Exception();
00228 }
00229 SBPL_Trajectory_t traj;
00230
00231
00232 if(fscanf(fDynObs, "%s", sTemp) != 1){
00233 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00234 throw new SBPL_Exception();
00235 }
00236 strcpy(sTemp1, "TrajectoryProbability:");
00237 if(strcmp(sTemp1, sTemp) != 0){
00238 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00239 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00240 throw new SBPL_Exception();
00241 }
00242 if(fscanf(fDynObs, "%s", sTemp) != 1){
00243 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00244 throw new SBPL_Exception();
00245 }
00246 traj.prob = atof(sTemp);
00247 if(traj.prob < 0 || traj.prob > 1){
00248 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00249 SBPL_PRINTF("Expected TrajectoryProbability on the interval [0,1] but got %f\n", traj.prob);
00250 throw new SBPL_Exception();
00251 }
00252 trajProbSum += traj.prob;
00253
00254
00255 if(fscanf(fDynObs, "%s", sTemp) != 1){
00256 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00257 throw new SBPL_Exception();
00258 }
00259 strcpy(sTemp1, "NumberOfPoints:");
00260 if(strcmp(sTemp1, sTemp) != 0){
00261 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00262 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00263 throw new SBPL_Exception();
00264 }
00265 if(fscanf(fDynObs, "%s", sTemp) != 1){
00266 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00267 throw new SBPL_Exception();
00268 }
00269 int numPoints = atoi(sTemp);
00270
00271
00272 int prev_t = 0;
00273 for(int k=0; k < numPoints; k++){
00274
00275 SBPL_Traj_Pt_t pt;
00276 if(fscanf(fDynObs, "%s", sTemp) != 1){
00277 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00278 throw new SBPL_Exception();
00279 }
00280 pt.x = atof(sTemp);
00281 if(fscanf(fDynObs, "%s", sTemp) != 1){
00282 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00283 throw new SBPL_Exception();
00284 }
00285 pt.y = atof(sTemp);
00286 if(fscanf(fDynObs, "%s", sTemp) != 1){
00287 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00288 throw new SBPL_Exception();
00289 }
00290 pt.t = CONTTIME2DISC(atof(sTemp),envSIPPLatCfg.timeResolution);
00291
00292 if(prev_t > pt.t && k != 0){
00293 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00294 SBPL_PRINTF("dynamic obstacle trajectory times can't decrease!\n");
00295 throw new SBPL_Exception();
00296 }
00297 prev_t = pt.t;
00298
00299 if(fscanf(fDynObs, "%s", sTemp) != 1){
00300 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00301 throw new SBPL_Exception();
00302 }
00303 pt.std_dev = atof(sTemp);
00304
00305
00306 traj.points.push_back(pt);
00307 }
00308
00309
00310
00311 if(fscanf(fDynObs, "%s", sTemp) != 1){
00312 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00313 throw new SBPL_Exception();
00314 }
00315 strcpy(sTemp1, "ObstacleExistsAfterTrajectory:");
00316 if(strcmp(sTemp1, sTemp) != 0){
00317 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00318 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00319 throw new SBPL_Exception();
00320 }
00321 if(fscanf(fDynObs, "%s", sTemp) != 1){
00322 SBPL_ERROR("ERROR: ran out of dynamic obstacle file early\n");
00323 throw new SBPL_Exception();
00324 }
00325 traj.existsAfter = atoi(sTemp);
00326 if(traj.existsAfter != 0 && traj.existsAfter != 1){
00327 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00328 SBPL_PRINTF("ObstacleExistsAfterTrajectory is a boolean and needs to be 0 or 1\n");
00329 throw new SBPL_Exception();
00330 }
00331
00332
00333 obs.trajectories.push_back(traj);
00334 }
00335
00336
00337 if(fabs(trajProbSum - 1.0) > ERR_EPS){
00338 SBPL_ERROR("ERROR: dynamic obstacle file has incorrect format\n");
00339 SBPL_PRINTF("Probabilities for trajectories of dynamic obstacle %d sum to %f instead of 1\n", i, trajProbSum);
00340 throw new SBPL_Exception();
00341 }
00342
00343
00344 dynamicObstacles.push_back(obs);
00345
00346 }
00347
00348
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358
00359 SBPL_PRINTF("Done Reading Dynamic Obstacles\n");
00360 }
00361
00362 void EnvSIPPLattice::InitializeTimelineMap(){
00363 SBPL_PRINTF("Initializing interval and timeline maps\n");
00364
00365 intervalMap.resize(envSIPPLatCfg.EnvWidth_c);
00366 timelineMap.resize(envSIPPLatCfg.EnvWidth_c);
00367 for (int x = 0; x < envSIPPLatCfg.EnvWidth_c; x++){
00368 intervalMap[x].resize(envSIPPLatCfg.EnvHeight_c);
00369 timelineMap[x].resize(envSIPPLatCfg.EnvHeight_c);
00370 }
00371
00372 UpdateTimelineMap();
00373 }
00374
00375 bool EnvSIPPLattice::UpdateTimelineMap(){
00376 SBPL_PRINTF("clearing interval map\n");
00377
00378 for(unsigned int x=0; x<intervalMap.size(); x++){
00379 for(unsigned int y=0; y<intervalMap[x].size(); y++){
00380 intervalMap[x][y].clear();
00381 timelineMap[x][y].clear();
00382 }
00383 }
00384
00385 SBPL_PRINTF("filling in new interval map\n");
00386
00387 for(unsigned int i=0; i<dynamicObstacles.size(); i++){
00388 for(unsigned int j=0; j<dynamicObstacles[i].trajectories.size(); j++){
00389
00390 for(unsigned int k=0; k<dynamicObstacles[i].trajectories[j].points.size(); k++){
00391 SBPL_Traj_Pt_t p = dynamicObstacles[i].trajectories[j].points[k];
00392
00393
00394
00395 int bubble_cell_rad = (int)ceil((dynamicObstacles[i].radius + p.std_dev*3)/envSIPPLatCfg.cellsize_m)+1;
00396 FillInBubble(CONTXY2DISC(p.x, envSIPPLatCfg.cellsize_m), CONTXY2DISC(p.y, envSIPPLatCfg.cellsize_m), p.t, bubble_cell_rad);
00397 }
00398 }
00399 }
00400
00401 SBPL_PRINTF("creating timeline map\n");
00402 for(unsigned int x=0; x<timelineMap.size(); x++){
00403 for(unsigned int y=0; y<timelineMap[x].size(); y++){
00404 intervals2Timeline(x,y);
00405 }
00406 }
00407
00408 #if DRAW_MAP
00409 SBPL_PRINTF("intervalMap\n");
00410
00411 for(int y = 0; y < envSIPPLatCfg.EnvHeight_c; y++){
00412 for(int x = 0; x < envSIPPLatCfg.EnvWidth_c; x++){
00413 SBPL_PRINTF("(");
00414 for(unsigned int i=0; i<intervalMap[x][y].size(); i++)
00415 SBPL_PRINTF("%d %d,",intervalMap[x][y][i].first,intervalMap[x][y][i].second);
00416 SBPL_PRINTF(") ");
00417 }
00418 SBPL_PRINTF("\n");
00419 }
00420 SBPL_PRINTF("timelineMap\n");
00421
00422 for(int y = 0; y < envSIPPLatCfg.EnvHeight_c; y++){
00423 for(int x = 0; x < envSIPPLatCfg.EnvWidth_c; x++){
00424 SBPL_PRINTF("(");
00425 for(unsigned int i=0; i<timelineMap[x][y].size(); i++)
00426 SBPL_PRINTF("%d,",timelineMap[x][y][i]);
00427 SBPL_PRINTF(") ");
00428 }
00429 SBPL_PRINTF("\n");
00430 }
00431 #endif
00432
00433 SBPL_PRINTF("done updating timeline map\n");
00434
00435
00436 if(envSIPPLat.bInitialized){
00437 envSIPPLatHashEntry_t* HashEntry = getEntryFromID(envSIPPLat.startstateid);
00438 int interval = getInterval(HashEntry->X, HashEntry->Y, HashEntry->T);
00439 HashEntry->Interval = interval;
00440 return interval >= 0;
00441 }
00442 return true;
00443 }
00444
00445
00446 void EnvSIPPLattice::FillInBubble(int CenterX, int CenterY, int T, int rad){
00447
00448 int d = 3 - 2*rad;
00449 int x = 0;
00450 int y = rad;
00451
00452 while(x <= y){
00453
00454 FillInBubbleColumn(CenterX-y, CenterY+x, CenterY-x, T);
00455 FillInBubbleColumn(CenterX-x, CenterY+y, CenterY-y, T);
00456 FillInBubbleColumn(CenterX+x, CenterY+y, CenterY-y, T);
00457 FillInBubbleColumn(CenterX+y, CenterY+x, CenterY-x, T);
00458 if(d <= 0)
00459 d += 4*x + 6;
00460 else{
00461 d += 4*(x-y) + 10;
00462 y--;
00463 }
00464 x++;
00465 }
00466
00467 }
00468
00469 void EnvSIPPLattice::FillInBubbleColumn(int x, int topY, int botY, int T){
00470
00471
00472 if(x < 0 || x >= (int)intervalMap.size())
00473 return;
00474
00475 if(topY >= (int)intervalMap[x].size())
00476 topY = intervalMap[x].size()-1;
00477 if(botY < 0)
00478 botY = 0;
00479
00480 if(topY < 0 || botY >= (int)intervalMap[x].size())
00481 return;
00482
00483
00484
00485 FillInBubbleCell(x, topY, T);
00486
00487
00488
00489 FillInBubbleCell(x, botY, T);
00490
00491
00492
00493
00494 if(topY-botY <= 1)
00495 return;
00496
00497
00498 for(int y = topY-1; y>botY; y--){
00499 FillInBubbleCell(x, y, T);
00500 }
00501
00502
00503 }
00504
00505 void EnvSIPPLattice::FillInBubbleCell(int x, int y, int T){
00506 int minT = T - temporal_padding;
00507 int maxT = T + temporal_padding;
00508 intervalMap[x][y].push_back(pair<int,int>(minT,maxT));
00509 }
00510
00511 void EnvSIPPLattice::intervals2Timeline(int x, int y){
00512 if(intervalMap[x][y].empty())
00513 return;
00514 sort(intervalMap[x][y].begin(), intervalMap[x][y].end(), pairCompare);
00515 timelineMap[x][y].push_back(intervalMap[x][y][0].first);
00516 timelineMap[x][y].push_back(intervalMap[x][y][0].second + 1);
00517 for(unsigned int i=1; i<intervalMap[x][y].size(); i++){
00518 if(intervalMap[x][y][i].first <= timelineMap[x][y].back() && intervalMap[x][y][i].second >= timelineMap[x][y].back())
00519 timelineMap[x][y].back() = intervalMap[x][y][i].second + 1;
00520 else if(intervalMap[x][y][i].first > timelineMap[x][y].back()){
00521 timelineMap[x][y].push_back(intervalMap[x][y][i].first);
00522 timelineMap[x][y].push_back(intervalMap[x][y][i].second + 1);
00523 }
00524 }
00525 }
00526
00527 int EnvSIPPLattice::getInterval(int x, int y, int t){
00528 int i = distance(timelineMap[x][y].begin(), upper_bound(timelineMap[x][y].begin(), timelineMap[x][y].end(), t));
00529 if(i%2)
00530 return -1;
00531 return i/2;
00532 }
00533
00534 void EnvSIPPLattice::getIntervals(vector<int>* intervals, vector<int>* times, envSIPPLatHashEntry_t* state, envSIPPLatAction_t* action){
00535 int newX = state->X + action->dX;
00536 int newY = state->Y + action->dY;
00537 int newT = state->T + action->dT;
00538
00539 int state_interval = getInterval(state->X, state->Y, state->T);
00540 int last_leave_t = (timelineMap[state->X][state->Y].size() <= (unsigned int)(state_interval*2+1) ? INFINITECOST : timelineMap[state->X][state->Y][state_interval*2+1]-1);
00541 int last_newT = last_leave_t + action->dT;
00542
00543 int firstInterval = distance(timelineMap[newX][newY].begin(), upper_bound(timelineMap[newX][newY].begin(), timelineMap[newX][newY].end(), newT));
00544 if(firstInterval%2)
00545 firstInterval++;
00546 firstInterval = firstInterval/2;
00547 int lastInterval = distance(timelineMap[newX][newY].begin(), upper_bound(timelineMap[newX][newY].begin(), timelineMap[newX][newY].end(), last_newT));
00548 if(lastInterval%2)
00549 lastInterval--;
00550 lastInterval = lastInterval/2;
00551
00552 if(lastInterval < firstInterval)
00553 return;
00554
00555
00556
00557 int t;
00558 if(lastInterval == firstInterval){
00559 t = getArrivalTimeToInterval(state, action, newT, last_newT);
00560 if(t >= 0){
00561 intervals->push_back(firstInterval);
00562 times->push_back(t);
00563 }
00564 return;
00565 }
00566
00567
00568 t = getArrivalTimeToInterval(state, action, newT, timelineMap[newX][newY][firstInterval*2]-1);
00569 if(t >= 0){
00570 intervals->push_back(firstInterval);
00571 times->push_back(t);
00572 }
00573
00574
00575 for(int i = firstInterval+1; i<lastInterval; i++){
00576 t = getArrivalTimeToInterval(state, action, timelineMap[newX][newY][i*2-1], timelineMap[newX][newY][i*2]-1);
00577 if(t >= 0){
00578 intervals->push_back(i);
00579 times->push_back(t);
00580 }
00581
00582 }
00583
00584
00585 t = getArrivalTimeToInterval(state, action, timelineMap[newX][newY][lastInterval*2-1], last_newT);
00586 if(t >= 0){
00587 intervals->push_back(lastInterval);
00588 times->push_back(t);
00589 }
00590 }
00591
00592
00593 int EnvSIPPLattice::getArrivalTimeToInterval(envSIPPLatHashEntry_t* state, envSIPPLatAction_t* action, int start_t, int end_t){
00594 for(int t=start_t - action->dT; t<=end_t - action->dT;){
00595
00596 bool collision = false;
00597 for(unsigned int i=0; i<action->interm4DcellsV.size(); i++){
00598 SBPL_4Dcell_t cell = action->interm4DcellsV.at(i);
00599 cell.x = cell.x + state->X;
00600 cell.y = cell.y + state->Y;
00601 cell.t = cell.t + t;
00602
00603
00604 int interval = distance(timelineMap[cell.x][cell.y].begin(), upper_bound(timelineMap[cell.x][cell.y].begin(), timelineMap[cell.x][cell.y].end(), cell.t));
00605
00606 if(interval%2){
00607 t += timelineMap[cell.x][cell.y][interval] - cell.t;
00608 collision = true;
00609 break;
00610 }
00611 }
00612 if(!collision)
00613 return t + action->dT;
00614 }
00615 return -1;
00616 }
00617
00618 void EnvSIPPLattice::SetConfiguration(int width, int height,
00619 const unsigned char* mapdata,
00620 int startx, int starty, int starttheta, int startTime,
00621 int goalx, int goaly, int goaltheta,
00622 double cellsize_m, double timeResolution, double nominalvel_mpersecs, double timetoturn45degsinplace_secs,
00623 const vector<sbpl_2Dpt_t> & robot_perimeterV) {
00624 envSIPPLatCfg.EnvWidth_c = width;
00625 envSIPPLatCfg.EnvHeight_c = height;
00626 envSIPPLatCfg.StartX_c = startx;
00627 envSIPPLatCfg.StartY_c = starty;
00628 envSIPPLatCfg.StartTheta = starttheta;
00629 envSIPPLatCfg.StartTime = startTime;
00630
00631 if(envSIPPLatCfg.StartX_c < 0 || envSIPPLatCfg.StartX_c >= envSIPPLatCfg.EnvWidth_c) {
00632 SBPL_ERROR("ERROR: illegal start coordinates\n");
00633 throw new SBPL_Exception();
00634 }
00635 if(envSIPPLatCfg.StartY_c < 0 || envSIPPLatCfg.StartY_c >= envSIPPLatCfg.EnvHeight_c) {
00636 SBPL_ERROR("ERROR: illegal start coordinates\n");
00637 throw new SBPL_Exception();
00638 }
00639 if(envSIPPLatCfg.StartTheta < 0 || envSIPPLatCfg.StartTheta >= ENVSIPPLAT_THETADIRS) {
00640 SBPL_ERROR("ERROR: illegal start coordinates for theta\n");
00641 throw new SBPL_Exception();
00642 }
00643
00644 envSIPPLatCfg.EndX_c = goalx;
00645 envSIPPLatCfg.EndY_c = goaly;
00646 envSIPPLatCfg.EndTheta = goaltheta;
00647
00648 if(envSIPPLatCfg.EndX_c < 0 || envSIPPLatCfg.EndX_c >= envSIPPLatCfg.EnvWidth_c) {
00649 SBPL_ERROR("ERROR: illegal goal coordinates\n");
00650 throw new SBPL_Exception();
00651 }
00652 if(envSIPPLatCfg.EndY_c < 0 || envSIPPLatCfg.EndY_c >= envSIPPLatCfg.EnvHeight_c) {
00653 SBPL_ERROR("ERROR: illegal goal coordinates\n");
00654 throw new SBPL_Exception();
00655 }
00656 if(envSIPPLatCfg.EndTheta < 0 || envSIPPLatCfg.EndTheta >= ENVSIPPLAT_THETADIRS) {
00657 SBPL_ERROR("ERROR: illegal goal coordinates for theta\n");
00658 throw new SBPL_Exception();
00659 }
00660
00661 envSIPPLatCfg.FootprintPolygon = robot_perimeterV;
00662
00663 envSIPPLatCfg.nominalvel_mpersecs = nominalvel_mpersecs;
00664 envSIPPLatCfg.cellsize_m = cellsize_m;
00665 envSIPPLatCfg.timeResolution = timeResolution;
00666 envSIPPLatCfg.timetoturn45degsinplace_secs = timetoturn45degsinplace_secs;
00667
00668
00669
00670 envSIPPLatCfg.Grid2D = new unsigned char* [envSIPPLatCfg.EnvWidth_c];
00671 for (int x = 0; x < envSIPPLatCfg.EnvWidth_c; x++) {
00672 envSIPPLatCfg.Grid2D[x] = new unsigned char [envSIPPLatCfg.EnvHeight_c];
00673 }
00674
00675
00676 if (0 == mapdata) {
00677 for (int y = 0; y < envSIPPLatCfg.EnvHeight_c; y++) {
00678 for (int x = 0; x < envSIPPLatCfg.EnvWidth_c; x++) {
00679 envSIPPLatCfg.Grid2D[x][y] = 0;
00680 }
00681 }
00682 }
00683 else {
00684 for (int y = 0; y < envSIPPLatCfg.EnvHeight_c; y++) {
00685 for (int x = 0; x < envSIPPLatCfg.EnvWidth_c; x++) {
00686 envSIPPLatCfg.Grid2D[x][y] = mapdata[x+y*width];
00687 }
00688 }
00689 }
00690 }
00691
00692 void EnvSIPPLattice::ReadConfiguration(FILE* fCfg)
00693 {
00694
00695 char sTemp[1024], sTemp1[1024];
00696 int dTemp;
00697 int x, y;
00698
00699
00700 if(fscanf(fCfg, "%s", sTemp) != 1){
00701 SBPL_ERROR("ERROR: ran out of env file early\n");
00702 throw new SBPL_Exception();
00703 }
00704 strcpy(sTemp1, "discretization(cells):");
00705 if(strcmp(sTemp1, sTemp) != 0)
00706 {
00707 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00708 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00709 throw new SBPL_Exception();
00710 }
00711 if(fscanf(fCfg, "%s", sTemp) != 1){
00712 SBPL_ERROR("ERROR: ran out of env file early\n");
00713 throw new SBPL_Exception();
00714 }
00715 envSIPPLatCfg.EnvWidth_c = atoi(sTemp);
00716 if(fscanf(fCfg, "%s", sTemp) != 1){
00717 SBPL_ERROR("ERROR: ran out of env file early\n");
00718 throw new SBPL_Exception();
00719 }
00720 envSIPPLatCfg.EnvHeight_c = atoi(sTemp);
00721
00722
00723 if(fscanf(fCfg, "%s", sTemp) != 1){
00724 SBPL_ERROR("ERROR: ran out of env file early\n");
00725 throw new SBPL_Exception();
00726 }
00727 strcpy(sTemp1, "obsthresh:");
00728 if(strcmp(sTemp1, sTemp) != 0)
00729 {
00730 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00731 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00732 SBPL_PRINTF("see existing examples of env files for the right format of heading\n");
00733 throw new SBPL_Exception();
00734 }
00735 if(fscanf(fCfg, "%s", sTemp) != 1){
00736 SBPL_ERROR("ERROR: ran out of env file early\n");
00737 throw new SBPL_Exception();
00738 }
00739 envSIPPLatCfg.obsthresh = atoi(sTemp);
00740 SBPL_PRINTF("obsthresh = %d\n", envSIPPLatCfg.obsthresh);
00741
00742
00743 if(fscanf(fCfg, "%s", sTemp) != 1){
00744 SBPL_ERROR("ERROR: ran out of env file early\n");
00745 throw new SBPL_Exception();
00746 }
00747 strcpy(sTemp1, "cost_inscribed_thresh:");
00748 if(strcmp(sTemp1, sTemp) != 0)
00749 {
00750 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00751 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00752 SBPL_PRINTF("see existing examples of env files for the right format of heading\n");
00753 throw new SBPL_Exception();
00754 }
00755 if(fscanf(fCfg, "%s", sTemp) != 1){
00756 SBPL_ERROR("ERROR: ran out of env file early\n");
00757 throw new SBPL_Exception();
00758 }
00759 envSIPPLatCfg.cost_inscribed_thresh = atoi(sTemp);
00760 SBPL_PRINTF("cost_inscribed_thresh = %d\n", envSIPPLatCfg.cost_inscribed_thresh);
00761
00762
00763
00764 if(fscanf(fCfg, "%s", sTemp) != 1){
00765 SBPL_ERROR("ERROR: ran out of env file early\n");
00766 throw new SBPL_Exception();
00767 }
00768 strcpy(sTemp1, "cost_possibly_circumscribed_thresh:");
00769 if(strcmp(sTemp1, sTemp) != 0)
00770 {
00771 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00772 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00773 SBPL_PRINTF("see existing examples of env files for the right format of heading\n");
00774 throw new SBPL_Exception();
00775 }
00776 if(fscanf(fCfg, "%s", sTemp) != 1){
00777 SBPL_ERROR("ERROR: ran out of env file early\n");
00778 throw new SBPL_Exception();
00779 }
00780 envSIPPLatCfg.cost_possibly_circumscribed_thresh = atoi(sTemp);
00781 SBPL_PRINTF("cost_possibly_circumscribed_thresh = %d\n", envSIPPLatCfg.cost_possibly_circumscribed_thresh);
00782
00783
00784 if(fscanf(fCfg, "%s", sTemp) != 1){
00785 SBPL_ERROR("ERROR: ran out of env file early\n");
00786 throw new SBPL_Exception();
00787 }
00788 strcpy(sTemp1, "dynamic_obstacle_collision_cost_thresh:");
00789 if(strcmp(sTemp1, sTemp) != 0)
00790 {
00791 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00792 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00793 SBPL_PRINTF("see existing examples of env files for the right format of heading\n");
00794 throw new SBPL_Exception();
00795 }
00796 if(fscanf(fCfg, "%s", sTemp) != 1){
00797 SBPL_ERROR("ERROR: ran out of env file early\n");
00798 throw new SBPL_Exception();
00799 }
00800 envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh = atoi(sTemp);
00801 SBPL_PRINTF("dynamic_obstacle_collision_cost_thresh = %d\n", envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh);
00802
00803
00804 if(fscanf(fCfg, "%s", sTemp) != 1){
00805 SBPL_ERROR("ERROR: ran out of env file early\n");
00806 throw new SBPL_Exception();
00807 }
00808 strcpy(sTemp1, "cellsize(meters):");
00809 if(strcmp(sTemp1, sTemp) != 0)
00810 {
00811 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00812 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00813 throw new SBPL_Exception();
00814 }
00815 if(fscanf(fCfg, "%s", sTemp) != 1){
00816 SBPL_ERROR("ERROR: ran out of env file early\n");
00817 throw new SBPL_Exception();
00818 }
00819 envSIPPLatCfg.cellsize_m = atof(sTemp);
00820
00821
00822 if(fscanf(fCfg, "%s", sTemp) != 1){
00823 SBPL_ERROR("ERROR: ran out of env file early\n");
00824 throw new SBPL_Exception();
00825 }
00826 strcpy(sTemp1, "timeResolution(seconds):");
00827 if(strcmp(sTemp1, sTemp) != 0)
00828 {
00829 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00830 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00831 throw new SBPL_Exception();
00832 }
00833 if(fscanf(fCfg, "%s", sTemp) != 1){
00834 SBPL_ERROR("ERROR: ran out of env file early\n");
00835 throw new SBPL_Exception();
00836 }
00837 envSIPPLatCfg.timeResolution = atof(sTemp);
00838
00839
00840 if(fscanf(fCfg, "%s", sTemp) != 1){
00841 SBPL_ERROR("ERROR: ran out of env file early\n");
00842 throw new SBPL_Exception();
00843 }
00844 strcpy(sTemp1, "temporal_padding(seconds):");
00845 if(strcmp(sTemp1, sTemp) != 0)
00846 {
00847 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00848 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00849 SBPL_PRINTF("see existing examples of env files for the right format of heading\n");
00850 throw new SBPL_Exception();
00851 }
00852 if(fscanf(fCfg, "%s", sTemp) != 1){
00853 SBPL_ERROR("ERROR: ran out of env file early\n");
00854 throw new SBPL_Exception();
00855 }
00856 temporal_padding = (int)ceil(atof(sTemp)/envSIPPLatCfg.timeResolution);
00857 SBPL_PRINTF("temporal_padding = %d\n", temporal_padding);
00858
00859
00860 if(fscanf(fCfg, "%s", sTemp) != 1){
00861 SBPL_ERROR("ERROR: ran out of env file early\n");
00862 throw new SBPL_Exception();
00863 }
00864 strcpy(sTemp1, "nominalvel(mpersecs):");
00865 if(strcmp(sTemp1, sTemp) != 0)
00866 {
00867 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00868 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00869 throw new SBPL_Exception();
00870 }
00871 if(fscanf(fCfg, "%s", sTemp) != 1){
00872 SBPL_ERROR("ERROR: ran out of env file early\n");
00873 throw new SBPL_Exception();
00874 }
00875 envSIPPLatCfg.nominalvel_mpersecs = atof(sTemp);
00876 if(fscanf(fCfg, "%s", sTemp) != 1){
00877 SBPL_ERROR("ERROR: ran out of env file early\n");
00878 throw new SBPL_Exception();
00879 }
00880 strcpy(sTemp1, "timetoturn45degsinplace(secs):");
00881 if(strcmp(sTemp1, sTemp) != 0)
00882 {
00883 SBPL_ERROR("ERROR: configuration file has incorrect format\n");
00884 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp);
00885 throw new SBPL_Exception();
00886 }
00887 if(fscanf(fCfg, "%s", sTemp) != 1){
00888 SBPL_ERROR("ERROR: ran out of env file early\n");
00889 throw new SBPL_Exception();
00890 }
00891 envSIPPLatCfg.timetoturn45degsinplace_secs = atof(sTemp);
00892
00893
00894
00895 if(fscanf(fCfg, "%s", sTemp) != 1){
00896 SBPL_ERROR("ERROR: ran out of env file early\n");
00897 throw new SBPL_Exception();
00898 }
00899 if(fscanf(fCfg, "%s", sTemp) != 1){
00900 SBPL_ERROR("ERROR: ran out of env file early\n");
00901 throw new SBPL_Exception();
00902 }
00903 envSIPPLatCfg.StartX_c = CONTXY2DISC(atof(sTemp),envSIPPLatCfg.cellsize_m);
00904 if(fscanf(fCfg, "%s", sTemp) != 1){
00905 SBPL_ERROR("ERROR: ran out of env file early\n");
00906 throw new SBPL_Exception();
00907 }
00908 envSIPPLatCfg.StartY_c = CONTXY2DISC(atof(sTemp),envSIPPLatCfg.cellsize_m);
00909 if(fscanf(fCfg, "%s", sTemp) != 1){
00910 SBPL_ERROR("ERROR: ran out of env file early\n");
00911 throw new SBPL_Exception();
00912 }
00913 envSIPPLatCfg.StartTheta = ContTheta2Disc(atof(sTemp), ENVSIPPLAT_THETADIRS);
00914 if(fscanf(fCfg, "%s", sTemp) != 1){
00915 SBPL_ERROR("ERROR: ran out of env file early\n");
00916 throw new SBPL_Exception();
00917 }
00918 envSIPPLatCfg.StartTime = CONTTIME2DISC(atof(sTemp),envSIPPLatCfg.timeResolution);
00919
00920
00921 if(envSIPPLatCfg.StartX_c < 0 || envSIPPLatCfg.StartX_c >= envSIPPLatCfg.EnvWidth_c)
00922 {
00923 SBPL_ERROR("ERROR: illegal start coordinates\n");
00924 throw new SBPL_Exception();
00925 }
00926 if(envSIPPLatCfg.StartY_c < 0 || envSIPPLatCfg.StartY_c >= envSIPPLatCfg.EnvHeight_c)
00927 {
00928 SBPL_ERROR("ERROR: illegal start coordinates\n");
00929 throw new SBPL_Exception();
00930 }
00931 if(envSIPPLatCfg.StartTheta < 0 || envSIPPLatCfg.StartTheta >= ENVSIPPLAT_THETADIRS) {
00932 SBPL_ERROR("ERROR: illegal start coordinates for theta\n");
00933 throw new SBPL_Exception();
00934 }
00935
00936
00937 if(fscanf(fCfg, "%s", sTemp) != 1){
00938 SBPL_ERROR("ERROR: ran out of env file early\n");
00939 throw new SBPL_Exception();
00940 }
00941 if(fscanf(fCfg, "%s", sTemp) != 1){
00942 SBPL_ERROR("ERROR: ran out of env file early\n");
00943 throw new SBPL_Exception();
00944 }
00945 envSIPPLatCfg.EndX_c = CONTXY2DISC(atof(sTemp),envSIPPLatCfg.cellsize_m);
00946 if(fscanf(fCfg, "%s", sTemp) != 1){
00947 SBPL_ERROR("ERROR: ran out of env file early\n");
00948 throw new SBPL_Exception();
00949 }
00950 envSIPPLatCfg.EndY_c = CONTXY2DISC(atof(sTemp),envSIPPLatCfg.cellsize_m);
00951 if(fscanf(fCfg, "%s", sTemp) != 1){
00952 SBPL_ERROR("ERROR: ran out of env file early\n");
00953 throw new SBPL_Exception();
00954 }
00955 envSIPPLatCfg.EndTheta = ContTheta2Disc(atof(sTemp), ENVSIPPLAT_THETADIRS);;
00956
00957 if(envSIPPLatCfg.EndX_c < 0 || envSIPPLatCfg.EndX_c >= envSIPPLatCfg.EnvWidth_c)
00958 {
00959 SBPL_ERROR("ERROR: illegal end coordinates\n");
00960 throw new SBPL_Exception();
00961 }
00962 if(envSIPPLatCfg.EndY_c < 0 || envSIPPLatCfg.EndY_c >= envSIPPLatCfg.EnvHeight_c)
00963 {
00964 SBPL_ERROR("ERROR: illegal end coordinates\n");
00965 throw new SBPL_Exception();
00966 }
00967 if(envSIPPLatCfg.EndTheta < 0 || envSIPPLatCfg.EndTheta >= ENVSIPPLAT_THETADIRS) {
00968 SBPL_ERROR("ERROR: illegal goal coordinates for theta\n");
00969 throw new SBPL_Exception();
00970 }
00971
00972
00973
00974 if(fscanf(fCfg, "%s", sTemp) != 1){
00975 SBPL_ERROR("ERROR: ran out of env file early\n");
00976 throw new SBPL_Exception();
00977 }
00978 envSIPPLatCfg.Grid2D = new unsigned char* [envSIPPLatCfg.EnvWidth_c];
00979 for (x = 0; x < envSIPPLatCfg.EnvWidth_c; x++)
00980 {
00981 envSIPPLatCfg.Grid2D[x] = new unsigned char [envSIPPLatCfg.EnvHeight_c];
00982 }
00983
00984
00985 for (y = 0; y < envSIPPLatCfg.EnvHeight_c; y++){
00986 for (x = 0; x < envSIPPLatCfg.EnvWidth_c; x++)
00987 {
00988 if(fscanf(fCfg, "%d", &dTemp) != 1)
00989 {
00990 SBPL_ERROR("ERROR: incorrect format of config file (%d,%d)\n",y,x);
00991 throw new SBPL_Exception();
00992 }
00993
00994 envSIPPLatCfg.Grid2D[x][y] = dTemp;
00995 #if DRAW_MAP
00996 SBPL_PRINTF("%d ",envSIPPLatCfg.Grid2D[x][y]);
00997 #endif
00998 }
00999 #if DRAW_MAP
01000 SBPL_PRINTF("\n");
01001 #endif
01002 }
01003
01004
01005
01006
01007
01008
01009
01010 }
01011
01012 int EnvSIPPLattice::ReadinCell(SBPL_4Dcell_t* cell, char* fIn)
01013 {
01014 char* temp;
01015 char* sptr;
01016
01017 if((temp = strtok_r(fIn, " ", &sptr)) == NULL)
01018 return FAIL;
01019 cell->x = atoi(temp);
01020
01021 if((temp = strtok_r(NULL, " ", &sptr)) == NULL)
01022 return FAIL;
01023 cell->y = atoi(temp);
01024
01025 if((temp = strtok_r(NULL, " ", &sptr)) == NULL)
01026 return FAIL;
01027 cell->theta = atoi(temp);
01028
01029 cell->theta = NORMALIZEDISCTHETA(cell->theta, ENVSIPPLAT_THETADIRS);
01030
01031
01032 if((temp = strtok_r(NULL, " ", &sptr)) != NULL){
01033 cell->t = atoi(temp);
01034 return SUCCESS_WITH_TIME;
01035 }
01036
01037 return SUCCESS_NO_TIME;
01038 }
01039
01040 int EnvSIPPLattice::ReadinPose(SBPL_4Dpt_t* pose, char* fIn)
01041 {
01042 char* temp;
01043 char* sptr;
01044
01045 if((temp = strtok_r(fIn, " ", &sptr)) == NULL)
01046 return FAIL;
01047 pose->x = atof(temp);
01048
01049 if((temp = strtok_r(NULL, " ", &sptr)) == NULL)
01050 return FAIL;
01051 pose->y = atof(temp);
01052
01053 if((temp = strtok_r(NULL, " ", &sptr)) == NULL)
01054 return FAIL;
01055 pose->theta = atof(temp);
01056 pose->theta = normalizeAngle(pose->theta);
01057
01058
01059 if((temp = strtok_r(NULL, " ", &sptr)) != NULL){
01060 pose->t = atof(temp);
01061 return SUCCESS_WITH_TIME;
01062 }
01063
01064 return SUCCESS_NO_TIME;
01065 }
01066
01067 bool EnvSIPPLattice::ReadinMotionPrimitive(SBPL_xythetasipp_mprimitive* pMotPrim, FILE* fIn, bool &isWaitMotion)
01068 {
01069 int bufSize = 1024;
01070 char sTemp[bufSize];
01071 int dTemp;
01072 char sExpected[bufSize];
01073 int numofIntermPoses;
01074 bool timeGiven = true;
01075 int timeGivenTemp;
01076
01077
01078 strcpy(sExpected, "primID:");
01079 if(fscanf(fIn, "%s", sTemp) == 0)
01080 return false;
01081 if(strcmp(sTemp, sExpected) != 0){
01082 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01083 return false;
01084 }
01085 if(fscanf(fIn, "%d", &pMotPrim->motprimID) != 1)
01086 return false;
01087
01088
01089 strcpy(sExpected, "startangle_c:");
01090 if(fscanf(fIn, "%s", sTemp) == 0)
01091 return false;
01092 if(strcmp(sTemp, sExpected) != 0){
01093 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01094 return false;
01095 }
01096 if(fscanf(fIn, "%d", &dTemp) == 0)
01097 {
01098 SBPL_ERROR("ERROR reading startangle\n");
01099 return false;
01100 }
01101 pMotPrim->starttheta_c = dTemp;
01102
01103
01104 strcpy(sExpected, "endpose_c:");
01105 if(fscanf(fIn, "%s", sTemp) == 0)
01106 return false;
01107 if(strcmp(sTemp, sExpected) != 0){
01108 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01109 return false;
01110 }
01111
01112 if(fgets(sTemp, bufSize, fIn) == NULL)
01113 return false;
01114 timeGivenTemp = ReadinCell(&pMotPrim->endcell, sTemp);
01115 if(timeGivenTemp == FAIL){
01116 SBPL_ERROR("ERROR: failed to read in endsearchpose\n");
01117 return false;
01118 }
01119 else if(timeGivenTemp == SUCCESS_NO_TIME)
01120 timeGiven = false;
01121
01122
01123
01124 strcpy(sExpected, "additionalactioncostmult:");
01125 if(fscanf(fIn, "%s", sTemp) == 0)
01126 return false;
01127 if(strcmp(sTemp, sExpected) != 0){
01128 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01129 return false;
01130 }
01131 if(fscanf(fIn, "%d", &dTemp) != 1)
01132 return false;
01133 pMotPrim->additionalactioncostmult = dTemp;
01134
01135
01136 strcpy(sExpected, "intermediateposes:");
01137 if(fscanf(fIn, "%s", sTemp) == 0)
01138 return false;
01139 if(strcmp(sTemp, sExpected) != 0){
01140 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01141 return false;
01142 }
01143 if(fscanf(fIn, "%d", &numofIntermPoses) != 1)
01144 return false;
01145
01146
01147
01148 if(fgets(sTemp, bufSize, fIn) == NULL)
01149 return false;
01150 isWaitMotion = true;
01151 for(int i = 0; i < numofIntermPoses; i++){
01152 SBPL_4Dpt_t intermpose;
01153 if(fgets(sTemp, bufSize, fIn) == NULL)
01154 return false;
01155 timeGivenTemp = ReadinPose(&intermpose, sTemp);
01156 if(timeGivenTemp == FAIL){
01157 SBPL_ERROR("ERROR: failed to read in intermediate pose %d\n",i);
01158 return false;
01159 }
01160 else if(timeGivenTemp == SUCCESS_NO_TIME)
01161 timeGiven = false;
01162
01163 isWaitMotion = isWaitMotion && intermpose.x == 0 && intermpose.y == 0 && (i==0 || intermpose.theta == pMotPrim->intermptV.back().theta);
01164 pMotPrim->intermptV.push_back(intermpose);
01165 }
01166
01167
01168 if(!timeGiven){
01169 double x = pMotPrim->intermptV[pMotPrim->intermptV.size()-1].x;
01170 double y = pMotPrim->intermptV[pMotPrim->intermptV.size()-1].y;
01171 double theta = fabs(computeMinUnsignedAngleDiff(pMotPrim->intermptV[pMotPrim->intermptV.size()-1].theta,
01172 pMotPrim->intermptV[0].theta));
01173 double timeFromTranslation = sqrt(x*x + y*y)/envSIPPLatCfg.nominalvel_mpersecs;
01174 double timeFromRotation = theta/(PI_CONST/4.0)*envSIPPLatCfg.timetoturn45degsinplace_secs;
01175 double t = __max(timeFromTranslation, timeFromRotation);
01176 if(t == 0)
01177 t = envSIPPLatCfg.timeResolution;
01178
01179 pMotPrim->endcell.t = (int)ceil(t/envSIPPLatCfg.timeResolution);
01180 t = pMotPrim->endcell.t*envSIPPLatCfg.timeResolution;
01181 double step = t/(pMotPrim->intermptV.size()-1);
01182 double temp = 0;
01183 for(unsigned int i = 0; i < pMotPrim->intermptV.size(); i++){
01184 pMotPrim->intermptV[i].t = temp;
01185 temp += step;
01186 }
01187 }
01188
01189
01190
01191 SBPL_4Dpt_t sourcepose;
01192 sourcepose.x = DISCXY2CONT(0, envSIPPLatCfg.cellsize_m);
01193 sourcepose.y = DISCXY2CONT(0, envSIPPLatCfg.cellsize_m);
01194 sourcepose.theta = DiscTheta2Cont(pMotPrim->starttheta_c, ENVSIPPLAT_THETADIRS);
01195 sourcepose.t = 0;
01196 double mp_endx_m = sourcepose.x + pMotPrim->intermptV[pMotPrim->intermptV.size()-1].x;
01197 double mp_endy_m = sourcepose.y + pMotPrim->intermptV[pMotPrim->intermptV.size()-1].y;
01198 double mp_endtheta_rad = pMotPrim->intermptV[pMotPrim->intermptV.size()-1].theta;
01199 double mp_endt = pMotPrim->intermptV[pMotPrim->intermptV.size()-1].t;
01200 int endx_c = CONTXY2DISC(mp_endx_m, envSIPPLatCfg.cellsize_m);
01201 int endy_c = CONTXY2DISC(mp_endy_m, envSIPPLatCfg.cellsize_m);
01202 int endtheta_c = ContTheta2Disc(mp_endtheta_rad, ENVSIPPLAT_THETADIRS);
01203 int endt_c = CONTTIME2DISC(mp_endt, envSIPPLatCfg.timeResolution);
01204 if(endx_c != pMotPrim->endcell.x || endy_c != pMotPrim->endcell.y || endtheta_c != pMotPrim->endcell.theta || endt_c != pMotPrim->endcell.t)
01205 {
01206 SBPL_ERROR("ERROR: incorrect primitive %d with startangle=%d last interm point %f %f %f %f does not match end pose %d %d %d %d\n",
01207 pMotPrim->motprimID, pMotPrim->starttheta_c,
01208 pMotPrim->intermptV[pMotPrim->intermptV.size()-1].x, pMotPrim->intermptV[pMotPrim->intermptV.size()-1].y, pMotPrim->intermptV[pMotPrim->intermptV.size()-1].theta, pMotPrim->intermptV[pMotPrim->intermptV.size()-1].t,
01209 pMotPrim->endcell.x, pMotPrim->endcell.y,pMotPrim->endcell.theta,pMotPrim->endcell.t);
01210 return false;
01211 }
01212
01213 return true;
01214 }
01215
01216
01217
01218 bool EnvSIPPLattice::ReadMotionPrimitives(FILE* fMotPrims)
01219 {
01220 char sTemp[1024], sExpected[1024];
01221 float fTemp;
01222 int dTemp;
01223 int totalNumofActions = 0;
01224
01225 SBPL_PRINTF("Reading in motion primitives...");
01226
01227
01228 strcpy(sExpected, "resolution_m:");
01229 if(fscanf(fMotPrims, "%s", sTemp) == 0)
01230 return false;
01231 if(strcmp(sTemp, sExpected) != 0){
01232 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01233 return false;
01234 }
01235 if(fscanf(fMotPrims, "%f", &fTemp) == 0)
01236 return false;
01237 if(fabs(fTemp-envSIPPLatCfg.cellsize_m) > ERR_EPS){
01238 SBPL_ERROR("ERROR: invalid grid resolution %f (instead of %f) in the dynamics file\n",
01239 fTemp, envSIPPLatCfg.cellsize_m);
01240 return false;
01241 }
01242
01243
01244 strcpy(sExpected, "timeResolution:");
01245 if(fscanf(fMotPrims, "%s", sTemp) == 0)
01246 return false;
01247 if(strcmp(sTemp, sExpected) != 0){
01248 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01249 return false;
01250 }
01251 if(fscanf(fMotPrims, "%f", &fTemp) == 0)
01252 return false;
01253 if(fabs(fTemp-envSIPPLatCfg.timeResolution) > ERR_EPS){
01254 SBPL_ERROR("ERROR: invalid time resolution %f (instead of %f) in the dynamics file\n",
01255 fTemp, envSIPPLatCfg.timeResolution);
01256 return false;
01257 }
01258
01259
01260 strcpy(sExpected, "numberofangles:");
01261 if(fscanf(fMotPrims, "%s", sTemp) == 0)
01262 return false;
01263 if(strcmp(sTemp, sExpected) != 0){
01264 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01265 return false;
01266 }
01267 if(fscanf(fMotPrims, "%d", &dTemp) == 0)
01268 return false;
01269 if(dTemp != ENVSIPPLAT_THETADIRS){
01270 SBPL_ERROR("ERROR: invalid angular resolution %d angles (instead of %d angles) in the motion primitives file\n",
01271 dTemp, ENVSIPPLAT_THETADIRS);
01272 return false;
01273 }
01274
01275
01276
01277 strcpy(sExpected, "totalnumberofprimitives:");
01278 if(fscanf(fMotPrims, "%s", sTemp) == 0)
01279 return false;
01280 if(strcmp(sTemp, sExpected) != 0){
01281 SBPL_ERROR("ERROR: expected %s but got %s\n", sExpected, sTemp);
01282 return false;
01283 }
01284 if(fscanf(fMotPrims, "%d", &totalNumofActions) == 0){
01285 return false;
01286 }
01287
01288 vector<bool> waitMotFlags;
01289 waitMotFlags.resize(ENVSIPPLAT_THETADIRS);
01290 for(int i = 0; i < ENVSIPPLAT_THETADIRS; i++)
01291 waitMotFlags[i] = false;
01292 vector<SBPL_xythetasipp_mprimitive> waitMots;
01293 for(int i = 0; i < totalNumofActions; i++){
01294 SBPL_xythetasipp_mprimitive motprim;
01295
01296 bool isWaitMotion;
01297 if(EnvSIPPLattice::ReadinMotionPrimitive(&motprim, fMotPrims, isWaitMotion) == false)
01298 return false;
01299
01300 if(isWaitMotion){
01301 SBPL_PRINTF("WARN: wait motion in mprim file ignored\n");
01302 }
01303 else
01304 envSIPPLatCfg.mprimV.push_back(motprim);
01305
01306 }
01307
01308 SBPL_PRINTF("done ");
01309
01310 return true;
01311 }
01312
01313
01314 void EnvSIPPLattice::ComputeReplanningDataforAction(envSIPPLatAction_t* action)
01315 {
01316 int j;
01317
01318
01319 SBPL_4Dcell_t startcell4d, endcell4d;
01320 for(int i = 0; i < (int)action->intersectingcellsV.size(); i++)
01321 {
01322
01323
01324 startcell4d.theta = action->starttheta;
01325 startcell4d.x = - action->intersectingcellsV.at(i).x;
01326 startcell4d.y = - action->intersectingcellsV.at(i).y;
01327 startcell4d.t = - action->intersectingcellsV.at(i).t;
01328
01329
01330 endcell4d.theta = NORMALIZEDISCTHETA(action->endtheta, ENVSIPPLAT_THETADIRS);
01331 endcell4d.x = startcell4d.x + action->dX;
01332 endcell4d.y = startcell4d.y + action->dY;
01333 endcell4d.t = startcell4d.t + action->dT;
01334
01335
01336 for(j = 0; j < (int)affectedsuccstatesV.size(); j++)
01337 {
01338 if(affectedsuccstatesV.at(j) == endcell4d)
01339 break;
01340 }
01341 if (j == (int)affectedsuccstatesV.size())
01342 affectedsuccstatesV.push_back(endcell4d);
01343
01344 for(j = 0; j < (int)affectedpredstatesV.size(); j++)
01345 {
01346 if(affectedpredstatesV.at(j) == startcell4d)
01347 break;
01348 }
01349 if (j == (int)affectedpredstatesV.size())
01350 affectedpredstatesV.push_back(startcell4d);
01351
01352 }
01353
01354
01355
01356
01357
01358
01359 startcell4d.theta = action->starttheta;
01360 startcell4d.x = - 0;
01361 startcell4d.y = - 0;
01362 startcell4d.t = - 0;
01363
01364
01365 endcell4d.theta = NORMALIZEDISCTHETA(action->endtheta, ENVSIPPLAT_THETADIRS);
01366 endcell4d.x = startcell4d.x + action->dX;
01367 endcell4d.y = startcell4d.y + action->dY;
01368 endcell4d.t = startcell4d.y + action->dT;
01369
01370
01371 for(j = 0; j < (int)affectedsuccstatesV.size(); j++)
01372 {
01373 if(affectedsuccstatesV.at(j) == endcell4d)
01374 break;
01375 }
01376 if (j == (int)affectedsuccstatesV.size())
01377 affectedsuccstatesV.push_back(endcell4d);
01378
01379 for(j = 0; j < (int)affectedpredstatesV.size(); j++)
01380 {
01381 if(affectedpredstatesV.at(j) == startcell4d)
01382 break;
01383 }
01384 if (j == (int)affectedpredstatesV.size())
01385 affectedpredstatesV.push_back(startcell4d);
01386
01387
01388
01389
01390 startcell4d.theta = action->starttheta;
01391 startcell4d.x = - action->dX;
01392 startcell4d.y = - action->dY;
01393 startcell4d.t = - action->dT;
01394
01395
01396 endcell4d.theta = NORMALIZEDISCTHETA(action->endtheta, ENVSIPPLAT_THETADIRS);
01397 endcell4d.x = startcell4d.x + action->dX;
01398 endcell4d.y = startcell4d.y + action->dY;
01399 endcell4d.t = startcell4d.t + action->dT;
01400
01401 for(j = 0; j < (int)affectedsuccstatesV.size(); j++)
01402 {
01403 if(affectedsuccstatesV.at(j) == endcell4d)
01404 break;
01405 }
01406 if (j == (int)affectedsuccstatesV.size())
01407 affectedsuccstatesV.push_back(endcell4d);
01408
01409 for(j = 0; j < (int)affectedpredstatesV.size(); j++)
01410 {
01411 if(affectedpredstatesV.at(j) == startcell4d)
01412 break;
01413 }
01414 if (j == (int)affectedpredstatesV.size())
01415 affectedpredstatesV.push_back(startcell4d);
01416
01417
01418 }
01419
01420
01421
01422
01423 void EnvSIPPLattice::ComputeReplanningData()
01424 {
01425
01426
01427
01428 for(int tind = 0; tind < ENVSIPPLAT_THETADIRS; tind++)
01429 {
01430
01431 for(int aind = 0; aind < envSIPPLatCfg.actionwidth; aind++)
01432 {
01433
01434 ComputeReplanningDataforAction(&envSIPPLatCfg.ActionsV[tind][aind]);
01435 }
01436 }
01437 }
01438
01439
01440 void EnvSIPPLattice::PrecomputeActionswithBaseMotionPrimitive(vector<SBPL_xythetasipp_mprimitive>* motionprimitiveV)
01441 {
01442
01443 SBPL_PRINTF("Pre-computing action data using base motion primitives...\n");
01444 envSIPPLatCfg.ActionsV = new envSIPPLatAction_t* [ENVSIPPLAT_THETADIRS];
01445 envSIPPLatCfg.PredActionsV = new vector<envSIPPLatAction_t*> [ENVSIPPLAT_THETADIRS];
01446 vector<sbpl_2Dcell_t> footprint;
01447
01448
01449 for(int tind = 0; tind < ENVSIPPLAT_THETADIRS; tind++)
01450 {
01451 SBPL_PRINTF("pre-computing action %d out of %d actions\n", tind, ENVSIPPLAT_THETADIRS);
01452 envSIPPLatCfg.ActionsV[tind] = new envSIPPLatAction_t[motionprimitiveV->size()];
01453
01454
01455 SBPL_4Dpt_t sourcepose;
01456 sourcepose.x = DISCXY2CONT(0, envSIPPLatCfg.cellsize_m);
01457 sourcepose.y = DISCXY2CONT(0, envSIPPLatCfg.cellsize_m);
01458 sourcepose.theta = DiscTheta2Cont(tind, ENVSIPPLAT_THETADIRS);
01459 sourcepose.t = DISCTIME2CONT(0, envSIPPLatCfg.timeResolution);
01460
01461
01462 for(size_t aind = 0; aind < motionprimitiveV->size(); aind++)
01463 {
01464 envSIPPLatCfg.ActionsV[tind][aind].starttheta = tind;
01465 double mp_endx_m = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size()-1].x;
01466 double mp_endy_m = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size()-1].y;
01467 double mp_endtheta_rad = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size()-1].theta;
01468 double mp_endt = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size()-1].t;
01469
01470 double endx = sourcepose.x + (mp_endx_m*cos(sourcepose.theta) - mp_endy_m*sin(sourcepose.theta));
01471 double endy = sourcepose.y + (mp_endx_m*sin(sourcepose.theta) + mp_endy_m*cos(sourcepose.theta));
01472
01473 int endx_c = CONTXY2DISC(endx, envSIPPLatCfg.cellsize_m);
01474 int endy_c = CONTXY2DISC(endy, envSIPPLatCfg.cellsize_m);
01475
01476
01477 envSIPPLatCfg.ActionsV[tind][aind].endtheta = ContTheta2Disc(mp_endtheta_rad+sourcepose.theta, ENVSIPPLAT_THETADIRS);
01478 envSIPPLatCfg.ActionsV[tind][aind].dX = endx_c;
01479 envSIPPLatCfg.ActionsV[tind][aind].dY = endy_c;
01480 envSIPPLatCfg.ActionsV[tind][aind].dT = CONTTIME2DISC(mp_endt + sourcepose.t, envSIPPLatCfg.timeResolution);
01481
01482
01483
01484
01485
01486
01487
01488
01489
01490
01491
01492
01493 envSIPPLatCfg.ActionsV[tind][aind].cost = (int)(ENVSIPPLAT_COSTMULT_MTOMM*envSIPPLatCfg.ActionsV[tind][aind].dT*envSIPPLatCfg.timeResolution);
01494
01495
01496
01497 envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV.clear();
01498 envSIPPLatCfg.ActionsV[tind][aind].intermptV.clear();
01499 envSIPPLatCfg.ActionsV[tind][aind].interm4DcellsV.clear();
01500 SBPL_4Dcell_t previnterm4Dcell;
01501 previnterm4Dcell.theta = previnterm4Dcell.x = previnterm4Dcell.y = previnterm4Dcell.t = 0;
01502 for (int pind = 0; pind < (int)motionprimitiveV->at(aind).intermptV.size(); pind++)
01503 {
01504 SBPL_4Dpt_t intermpt = motionprimitiveV->at(aind).intermptV[pind];
01505
01506
01507 double rotx = intermpt.x*cos(sourcepose.theta) - intermpt.y*sin(sourcepose.theta);
01508 double roty = intermpt.x*sin(sourcepose.theta) + intermpt.y*cos(sourcepose.theta);
01509 intermpt.x = rotx;
01510 intermpt.y = roty;
01511 intermpt.theta = normalizeAngle(sourcepose.theta + intermpt.theta);
01512
01513
01514
01515 envSIPPLatCfg.ActionsV[tind][aind].intermptV.push_back(intermpt);
01516
01517
01518 SBPL_4Dpt_t pose;
01519 pose = intermpt;
01520 pose.x += sourcepose.x;
01521 pose.y += sourcepose.y;
01522 pose.t += sourcepose.t;
01523 CalculateFootprintForPose(pose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01524
01525
01526 SBPL_4Dcell_t interm4Dcell;
01527 interm4Dcell.x = CONTXY2DISC(pose.x, envSIPPLatCfg.cellsize_m);
01528 interm4Dcell.y = CONTXY2DISC(pose.y, envSIPPLatCfg.cellsize_m);
01529 interm4Dcell.theta = ContTheta2Disc(pose.theta, ENVSIPPLAT_THETADIRS);
01530 interm4Dcell.t = CONTXY2DISC(pose.t, envSIPPLatCfg.timeResolution);
01531 if(envSIPPLatCfg.ActionsV[tind][aind].interm4DcellsV.size() == 0 ||
01532 previnterm4Dcell.theta != interm4Dcell.theta || previnterm4Dcell.x != interm4Dcell.x || previnterm4Dcell.y != interm4Dcell.y || previnterm4Dcell.t != interm4Dcell.t)
01533 {
01534 envSIPPLatCfg.ActionsV[tind][aind].interm4DcellsV.push_back(interm4Dcell);
01535 }
01536 previnterm4Dcell = interm4Dcell;
01537
01538 }
01539
01540
01541 RemoveSourceFootprint(sourcepose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01542
01543 #if DEBUG
01544 SBPL_FPRINTF(fDeb, "action tind=%d aind=%d: dX=%d dY=%d dT=%d endtheta=%d (%.2f degs -> %.2f degs) cost=%d (mprim: %.2f %.2f %.2f %.2f)\n",
01545 tind, aind,
01546 envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.ActionsV[tind][aind].dY, envSIPPLatCfg.ActionsV[tind][aind].dT,
01547 envSIPPLatCfg.ActionsV[tind][aind].endtheta, sourcepose.theta*180/PI_CONST,
01548 envSIPPLatCfg.ActionsV[tind][aind].intermptV[envSIPPLatCfg.ActionsV[tind][aind].intermptV.size()-1].theta*180/PI_CONST,
01549 envSIPPLatCfg.ActionsV[tind][aind].cost,
01550 mp_endx_m, mp_endy_m, mp_endt, mp_endtheta_rad);
01551 #endif
01552
01553
01554 int targettheta = envSIPPLatCfg.ActionsV[tind][aind].endtheta;
01555 if (targettheta < 0)
01556 targettheta = targettheta + ENVSIPPLAT_THETADIRS;
01557 envSIPPLatCfg.PredActionsV[targettheta].push_back(&(envSIPPLatCfg.ActionsV[tind][aind]));
01558
01559 }
01560 }
01561
01562
01563 envSIPPLatCfg.actionwidth = motionprimitiveV->size();
01564
01565
01566
01567 ComputeReplanningData();
01568
01569 SBPL_PRINTF("done pre-computing action data based on motion primitives\n");
01570
01571
01572 }
01573
01574
01575
01576 void EnvSIPPLattice::PrecomputeActionswithCompleteMotionPrimitive(vector<SBPL_xythetasipp_mprimitive>* motionprimitiveV)
01577 {
01578
01579 SBPL_PRINTF("Pre-computing action data using motion primitives for every angle...\n");
01580 envSIPPLatCfg.ActionsV = new envSIPPLatAction_t* [ENVSIPPLAT_THETADIRS];
01581 envSIPPLatCfg.PredActionsV = new vector<envSIPPLatAction_t*> [ENVSIPPLAT_THETADIRS];
01582 vector<sbpl_2Dcell_t> footprint;
01583
01584 if(motionprimitiveV->size()%ENVSIPPLAT_THETADIRS != 0)
01585 {
01586 SBPL_ERROR("ERROR: motionprimitives should be uniform across actions\n");
01587 throw new SBPL_Exception();
01588 }
01589
01590 envSIPPLatCfg.actionwidth = ((int)motionprimitiveV->size())/ENVSIPPLAT_THETADIRS;
01591
01592
01593 int maxnumofactions = 0;
01594 for(int tind = 0; tind < ENVSIPPLAT_THETADIRS; tind++)
01595 {
01596 SBPL_PRINTF("pre-computing action %d out of %d actions\n", tind, ENVSIPPLAT_THETADIRS);
01597
01598 envSIPPLatCfg.ActionsV[tind] = new envSIPPLatAction_t[envSIPPLatCfg.actionwidth];
01599
01600
01601 SBPL_4Dpt_t sourcepose;
01602 sourcepose.x = DISCXY2CONT(0, envSIPPLatCfg.cellsize_m);
01603 sourcepose.y = DISCXY2CONT(0, envSIPPLatCfg.cellsize_m);
01604 sourcepose.theta = DiscTheta2Cont(tind, ENVSIPPLAT_THETADIRS);
01605 sourcepose.t = DISCTIME2CONT(0, envSIPPLatCfg.timeResolution);
01606
01607
01608
01609 int numofactions = 0;
01610 int aind = -1;
01611 for(int mind = 0; mind < (int)motionprimitiveV->size(); mind++)
01612 {
01613
01614 if(motionprimitiveV->at(mind).starttheta_c != tind)
01615 continue;
01616
01617 aind++;
01618 numofactions++;
01619
01620
01621 envSIPPLatCfg.ActionsV[tind][aind].starttheta = tind;
01622
01623
01624 envSIPPLatCfg.ActionsV[tind][aind].endtheta = motionprimitiveV->at(mind).endcell.theta;
01625 envSIPPLatCfg.ActionsV[tind][aind].dX = motionprimitiveV->at(mind).endcell.x;
01626 envSIPPLatCfg.ActionsV[tind][aind].dY = motionprimitiveV->at(mind).endcell.y;
01627 envSIPPLatCfg.ActionsV[tind][aind].dT = motionprimitiveV->at(mind).endcell.t;
01628
01629
01630
01631
01632
01633
01634
01635
01636
01637
01638
01639
01640
01641
01642
01643
01644 envSIPPLatCfg.ActionsV[tind][aind].cost = (int)(ENVSIPPLAT_COSTMULT_MTOMM*envSIPPLatCfg.ActionsV[tind][aind].dT*envSIPPLatCfg.timeResolution);
01645
01646
01647
01648
01649
01650
01651 envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV.clear();
01652 envSIPPLatCfg.ActionsV[tind][aind].intermptV.clear();
01653 envSIPPLatCfg.ActionsV[tind][aind].interm4DcellsV.clear();
01654 SBPL_4Dcell_t previnterm4Dcell;
01655 previnterm4Dcell.theta = 0; previnterm4Dcell.x = 0; previnterm4Dcell.y = previnterm4Dcell.t = 0;
01656 for (int pind = 0; pind < (int)motionprimitiveV->at(mind).intermptV.size(); pind++)
01657 {
01658 SBPL_4Dpt_t intermpt = motionprimitiveV->at(mind).intermptV[pind];
01659
01660
01661 envSIPPLatCfg.ActionsV[tind][aind].intermptV.push_back(intermpt);
01662
01663
01664 SBPL_4Dpt_t pose;
01665 pose = intermpt;
01666 pose.x += sourcepose.x;
01667 pose.y += sourcepose.y;
01668 pose.t += sourcepose.t;
01669 CalculateFootprintForPose(pose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01670
01671
01672 SBPL_4Dcell_t interm4Dcell;
01673 interm4Dcell.x = CONTXY2DISC(pose.x, envSIPPLatCfg.cellsize_m);
01674 interm4Dcell.y = CONTXY2DISC(pose.y, envSIPPLatCfg.cellsize_m);
01675 interm4Dcell.theta = ContTheta2Disc(pose.theta, ENVSIPPLAT_THETADIRS);
01676 interm4Dcell.t = CONTTIME2DISC(pose.t, envSIPPLatCfg.timeResolution);
01677 if(envSIPPLatCfg.ActionsV[tind][aind].interm4DcellsV.size() == 0 ||
01678 previnterm4Dcell.theta != interm4Dcell.theta || previnterm4Dcell.x != interm4Dcell.x || previnterm4Dcell.y != interm4Dcell.y || previnterm4Dcell.t != interm4Dcell.t)
01679 {
01680 envSIPPLatCfg.ActionsV[tind][aind].interm4DcellsV.push_back(interm4Dcell);
01681 }
01682 previnterm4Dcell = interm4Dcell;
01683 }
01684
01685
01686 RemoveSourceFootprint(sourcepose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01687
01688 #if DEBUG
01689 SBPL_FPRINTF(fDeb, "action tind=%d aind=%d: dX=%d dY=%d dT=%d endtheta=%d (%.2f degs -> %.2f degs) cost=%d (mprimID %d: %d %d %d %d)\n",
01690 tind, aind,
01691 envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.ActionsV[tind][aind].dY, envSIPPLatCfg.ActionsV[tind][aind].dT,
01692 envSIPPLatCfg.ActionsV[tind][aind].endtheta,
01693 envSIPPLatCfg.ActionsV[tind][aind].intermptV[0].theta*180/PI_CONST,
01694 envSIPPLatCfg.ActionsV[tind][aind].intermptV[envSIPPLatCfg.ActionsV[tind][aind].intermptV.size()-1].theta*180/PI_CONST,
01695 envSIPPLatCfg.ActionsV[tind][aind].cost,
01696 motionprimitiveV->at(mind).motprimID,
01697 motionprimitiveV->at(mind).endcell.x, motionprimitiveV->at(mind).endcell.y, motionprimitiveV->at(mind).endcell.t, motionprimitiveV->at(mind).endcell.theta);
01698 #endif
01699
01700
01701 int targettheta = envSIPPLatCfg.ActionsV[tind][aind].endtheta;
01702 if (targettheta < 0)
01703 targettheta = targettheta + ENVSIPPLAT_THETADIRS;
01704 envSIPPLatCfg.PredActionsV[targettheta].push_back(&(envSIPPLatCfg.ActionsV[tind][aind]));
01705
01706 }
01707
01708 if(maxnumofactions < numofactions)
01709 maxnumofactions = numofactions;
01710 }
01711
01712
01713
01714
01715 if(motionprimitiveV->size() != (size_t)(ENVSIPPLAT_THETADIRS*maxnumofactions))
01716 {
01717 SBPL_ERROR("ERROR: nonuniform number of actions is not supported (maxnumofactions=%d while motprims=%d thetas=%d\n",
01718 maxnumofactions, (int)motionprimitiveV->size(), ENVSIPPLAT_THETADIRS);
01719 throw new SBPL_Exception();
01720 }
01721
01722
01723 ComputeReplanningData();
01724
01725 SBPL_PRINTF("done pre-computing action data based on motion primitives\n");
01726
01727 }
01728
01729 void EnvSIPPLattice::PrecomputeActions()
01730 {
01731 SBPL_PRINTF("not supported (costs are not computed right)!\n");
01732 throw new SBPL_Exception();
01733
01734
01735 SBPL_PRINTF("Pre-computing action data using the motion primitives for a 4D kinematic planning...\n");
01736 envSIPPLatCfg.ActionsV = new envSIPPLatAction_t* [ENVSIPPLAT_THETADIRS];
01737 envSIPPLatCfg.PredActionsV = new vector<envSIPPLatAction_t*> [ENVSIPPLAT_THETADIRS];
01738 vector<sbpl_2Dcell_t> footprint;
01739
01740 for(int tind = 0; tind < ENVSIPPLAT_THETADIRS; tind++)
01741 {
01742 SBPL_PRINTF("processing angle %d\n", tind);
01743 envSIPPLatCfg.ActionsV[tind] = new envSIPPLatAction_t[envSIPPLatCfg.actionwidth];
01744
01745
01746 SBPL_4Dpt_t sourcepose;
01747 sourcepose.x = DISCXY2CONT(0, envSIPPLatCfg.cellsize_m);
01748 sourcepose.y = DISCXY2CONT(0, envSIPPLatCfg.cellsize_m);
01749 sourcepose.theta = DiscTheta2Cont(tind, ENVSIPPLAT_THETADIRS);
01750 sourcepose.t = DISCTIME2CONT(0, envSIPPLatCfg.timeResolution);
01751
01752
01753 int aind = 0;
01754 for(; aind < 3; aind++)
01755 {
01756 envSIPPLatCfg.ActionsV[tind][aind].starttheta = tind;
01757 envSIPPLatCfg.ActionsV[tind][aind].endtheta = (tind + aind - 1)%ENVSIPPLAT_THETADIRS;
01758 double angle = DiscTheta2Cont(envSIPPLatCfg.ActionsV[tind][aind].endtheta, ENVSIPPLAT_THETADIRS);
01759 envSIPPLatCfg.ActionsV[tind][aind].dX = (int)(cos(angle) + 0.5*(cos(angle)>0?1:-1));
01760 envSIPPLatCfg.ActionsV[tind][aind].dY = (int)(sin(angle) + 0.5*(sin(angle)>0?1:-1));
01761
01762
01763 envSIPPLatCfg.ActionsV[tind][aind].dT = (int)(ceil(envSIPPLatCfg.cellsize_m/envSIPPLatCfg.nominalvel_mpersecs*sqrt((double)(envSIPPLatCfg.ActionsV[tind][aind].dX*envSIPPLatCfg.ActionsV[tind][aind].dX + envSIPPLatCfg.ActionsV[tind][aind].dY*envSIPPLatCfg.ActionsV[tind][aind].dY))));
01764 envSIPPLatCfg.ActionsV[tind][aind].cost = (int)(ceil(ENVSIPPLAT_COSTMULT_MTOMM*envSIPPLatCfg.cellsize_m/envSIPPLatCfg.nominalvel_mpersecs*sqrt((double)(envSIPPLatCfg.ActionsV[tind][aind].dX*envSIPPLatCfg.ActionsV[tind][aind].dX + envSIPPLatCfg.ActionsV[tind][aind].dY*envSIPPLatCfg.ActionsV[tind][aind].dY))));
01765
01766
01767 SBPL_4Dpt_t pose;
01768 pose.x = DISCXY2CONT(envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.cellsize_m);
01769 pose.y = DISCXY2CONT(envSIPPLatCfg.ActionsV[tind][aind].dY, envSIPPLatCfg.cellsize_m);
01770 pose.theta = angle;
01771 pose.t = DISCTIME2CONT(envSIPPLatCfg.ActionsV[tind][aind].dT, envSIPPLatCfg.timeResolution);
01772 envSIPPLatCfg.ActionsV[tind][aind].intermptV.clear();
01773 envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV.clear();
01774 CalculateFootprintForPose(pose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01775 RemoveSourceFootprint(sourcepose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01776
01777 #if DEBUG
01778 SBPL_PRINTF("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d dT=%d cost=%d\n",
01779 tind, aind, envSIPPLatCfg.ActionsV[tind][aind].endtheta, angle,
01780 envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.ActionsV[tind][aind].dY,
01781 envSIPPLatCfg.ActionsV[tind][aind].dT, envSIPPLatCfg.ActionsV[tind][aind].cost);
01782 #endif
01783
01784
01785 int targettheta = envSIPPLatCfg.ActionsV[tind][aind].endtheta;
01786 if (targettheta < 0)
01787 targettheta = targettheta + ENVSIPPLAT_THETADIRS;
01788 envSIPPLatCfg.PredActionsV[targettheta].push_back(&(envSIPPLatCfg.ActionsV[tind][aind]));
01789
01790 }
01791
01792
01793 aind = 3;
01794 envSIPPLatCfg.ActionsV[tind][aind].starttheta = tind;
01795 envSIPPLatCfg.ActionsV[tind][aind].endtheta = tind-1;
01796 if(envSIPPLatCfg.ActionsV[tind][aind].endtheta < 0) envSIPPLatCfg.ActionsV[tind][aind].endtheta += ENVSIPPLAT_THETADIRS;
01797 envSIPPLatCfg.ActionsV[tind][aind].dX = 0;
01798 envSIPPLatCfg.ActionsV[tind][aind].dY = 0;
01799 envSIPPLatCfg.ActionsV[tind][aind].dT = (int)(envSIPPLatCfg.timetoturn45degsinplace_secs);
01800 envSIPPLatCfg.ActionsV[tind][aind].cost = (int)(ENVSIPPLAT_COSTMULT_MTOMM*envSIPPLatCfg.timetoturn45degsinplace_secs);
01801
01802
01803 SBPL_4Dpt_t pose;
01804 pose.x = DISCXY2CONT(envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.cellsize_m);
01805 pose.y = DISCXY2CONT(envSIPPLatCfg.ActionsV[tind][aind].dY, envSIPPLatCfg.cellsize_m);
01806 pose.theta = DiscTheta2Cont(envSIPPLatCfg.ActionsV[tind][aind].endtheta, ENVSIPPLAT_THETADIRS);
01807 pose.t = DISCTIME2CONT(envSIPPLatCfg.ActionsV[tind][aind].dT, envSIPPLatCfg.timeResolution);
01808 envSIPPLatCfg.ActionsV[tind][aind].intermptV.clear();
01809 envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV.clear();
01810 CalculateFootprintForPose(pose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01811 RemoveSourceFootprint(sourcepose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01812
01813 #if DEBUG
01814 SBPL_PRINTF("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d dT=%d cost=%d\n",
01815 tind, aind, envSIPPLatCfg.ActionsV[tind][aind].endtheta, DiscTheta2Cont(envSIPPLatCfg.ActionsV[tind][aind].endtheta, ENVSIPPLAT_THETADIRS),
01816 envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.ActionsV[tind][aind].dY,
01817 envSIPPLatCfg.ActionsV[tind][aind].dT, envSIPPLatCfg.ActionsV[tind][aind].cost);
01818 #endif
01819
01820
01821 int targettheta = envSIPPLatCfg.ActionsV[tind][aind].endtheta;
01822 if (targettheta < 0)
01823 targettheta = targettheta + ENVSIPPLAT_THETADIRS;
01824 envSIPPLatCfg.PredActionsV[targettheta].push_back(&(envSIPPLatCfg.ActionsV[tind][aind]));
01825
01826
01827 aind = 4;
01828 envSIPPLatCfg.ActionsV[tind][aind].starttheta = tind;
01829 envSIPPLatCfg.ActionsV[tind][aind].endtheta = (tind + 1)%ENVSIPPLAT_THETADIRS;
01830 envSIPPLatCfg.ActionsV[tind][aind].dX = 0;
01831 envSIPPLatCfg.ActionsV[tind][aind].dY = 0;
01832 envSIPPLatCfg.ActionsV[tind][aind].dT = (int)(envSIPPLatCfg.timetoturn45degsinplace_secs);
01833 envSIPPLatCfg.ActionsV[tind][aind].cost = (int)(ENVSIPPLAT_COSTMULT_MTOMM*envSIPPLatCfg.timetoturn45degsinplace_secs);
01834
01835
01836 pose.x = DISCXY2CONT(envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.cellsize_m);
01837 pose.y = DISCXY2CONT(envSIPPLatCfg.ActionsV[tind][aind].dY, envSIPPLatCfg.cellsize_m);
01838 pose.theta = DiscTheta2Cont(envSIPPLatCfg.ActionsV[tind][aind].endtheta, ENVSIPPLAT_THETADIRS);
01839 pose.t = DISCTIME2CONT(envSIPPLatCfg.ActionsV[tind][aind].dT, envSIPPLatCfg.timeResolution);
01840 envSIPPLatCfg.ActionsV[tind][aind].intermptV.clear();
01841 envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV.clear();
01842 CalculateFootprintForPose(pose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01843 RemoveSourceFootprint(sourcepose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01844
01845
01846 #if DEBUG
01847 SBPL_PRINTF("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d dT=%d cost=%d\n",
01848 tind, aind, envSIPPLatCfg.ActionsV[tind][aind].endtheta, DiscTheta2Cont(envSIPPLatCfg.ActionsV[tind][aind].endtheta, ENVSIPPLAT_THETADIRS),
01849 envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.ActionsV[tind][aind].dY,
01850 envSIPPLatCfg.ActionsV[tind][aind].dT, envSIPPLatCfg.ActionsV[tind][aind].cost);
01851 #endif
01852
01853
01854 targettheta = envSIPPLatCfg.ActionsV[tind][aind].endtheta;
01855 if (targettheta < 0)
01856 targettheta = targettheta + ENVSIPPLAT_THETADIRS;
01857 envSIPPLatCfg.PredActionsV[targettheta].push_back(&(envSIPPLatCfg.ActionsV[tind][aind]));
01858
01859
01860 aind = 5;
01861 envSIPPLatCfg.ActionsV[tind][aind].starttheta = tind;
01862 envSIPPLatCfg.ActionsV[tind][aind].endtheta = tind;
01863 envSIPPLatCfg.ActionsV[tind][aind].dX = 0;
01864 envSIPPLatCfg.ActionsV[tind][aind].dY = 0;
01865 envSIPPLatCfg.ActionsV[tind][aind].dT = 1;
01866 envSIPPLatCfg.ActionsV[tind][aind].cost = (int)(ENVSIPPLAT_COSTMULT_MTOMM*envSIPPLatCfg.ActionsV[tind][aind].dT*envSIPPLatCfg.timeResolution);
01867
01868
01869
01870 pose.x = DISCXY2CONT(envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.cellsize_m);
01871 pose.y = DISCXY2CONT(envSIPPLatCfg.ActionsV[tind][aind].dY, envSIPPLatCfg.cellsize_m);
01872 pose.theta = DiscTheta2Cont(envSIPPLatCfg.ActionsV[tind][aind].endtheta, ENVSIPPLAT_THETADIRS);
01873 pose.t = DISCTIME2CONT(envSIPPLatCfg.ActionsV[tind][aind].dT, envSIPPLatCfg.timeResolution);
01874 envSIPPLatCfg.ActionsV[tind][aind].intermptV.clear();
01875 envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV.clear();
01876 CalculateFootprintForPose(pose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01877 RemoveSourceFootprint(sourcepose, &envSIPPLatCfg.ActionsV[tind][aind].intersectingcellsV);
01878
01879
01880 #if DEBUG
01881 SBPL_PRINTF("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d dT=%d cost=%d\n",
01882 tind, aind, envSIPPLatCfg.ActionsV[tind][aind].endtheta, DiscTheta2Cont(envSIPPLatCfg.ActionsV[tind][aind].endtheta, ENVSIPPLAT_THETADIRS),
01883 envSIPPLatCfg.ActionsV[tind][aind].dX, envSIPPLatCfg.ActionsV[tind][aind].dY,
01884 envSIPPLatCfg.ActionsV[tind][aind].dT, envSIPPLatCfg.ActionsV[tind][aind].cost);
01885 #endif
01886
01887
01888 targettheta = envSIPPLatCfg.ActionsV[tind][aind].endtheta;
01889 if (targettheta < 0)
01890 targettheta = targettheta + ENVSIPPLAT_THETADIRS;
01891 envSIPPLatCfg.PredActionsV[targettheta].push_back(&(envSIPPLatCfg.ActionsV[tind][aind]));
01892 }
01893
01894
01895 ComputeReplanningData();
01896
01897 SBPL_PRINTF("done pre-computing action data\n");
01898
01899
01900 }
01901
01902
01903
01904 void EnvSIPPLattice::InitializeEnvConfig(vector<SBPL_xythetasipp_mprimitive>* motionprimitiveV)
01905 {
01906
01907
01908
01909 envSIPPLatCfg.dXY[0][0] = -1;
01910 envSIPPLatCfg.dXY[0][1] = -1;
01911 envSIPPLatCfg.dXY[1][0] = -1;
01912 envSIPPLatCfg.dXY[1][1] = 0;
01913 envSIPPLatCfg.dXY[2][0] = -1;
01914 envSIPPLatCfg.dXY[2][1] = 1;
01915 envSIPPLatCfg.dXY[3][0] = 0;
01916 envSIPPLatCfg.dXY[3][1] = -1;
01917 envSIPPLatCfg.dXY[4][0] = 0;
01918 envSIPPLatCfg.dXY[4][1] = 1;
01919 envSIPPLatCfg.dXY[5][0] = 1;
01920 envSIPPLatCfg.dXY[5][1] = -1;
01921 envSIPPLatCfg.dXY[6][0] = 1;
01922 envSIPPLatCfg.dXY[6][1] = 0;
01923 envSIPPLatCfg.dXY[7][0] = 1;
01924 envSIPPLatCfg.dXY[7][1] = 1;
01925
01926
01927 SBPL_4Dpt_t temppose;
01928 temppose.x = 0.0;
01929 temppose.y = 0.0;
01930 temppose.theta = 0.0;
01931 temppose.t = 0.0;
01932 vector<SBPL_4Dcell_t> footprint;
01933 CalculateFootprintForPose(temppose, &footprint);
01934 SBPL_PRINTF("number of cells in footprint of the robot = %d\n", (int)footprint.size());
01935
01936 #if DEBUG
01937 SBPL_FPRINTF(fDeb, "footprint cells (size=%d):\n", footprint.size());
01938 for(int i = 0; i < (int) footprint.size(); i++)
01939 {
01940 SBPL_FPRINTF(fDeb, "%d %d (cont: %.3f %.3f)\n", footprint.at(i).x, footprint.at(i).y,
01941 DISCXY2CONT(footprint.at(i).x, envSIPPLatCfg.cellsize_m),
01942 DISCXY2CONT(footprint.at(i).y, envSIPPLatCfg.cellsize_m));
01943 }
01944 #endif
01945
01946
01947 if(motionprimitiveV == NULL)
01948 PrecomputeActions();
01949 else
01950 PrecomputeActionswithCompleteMotionPrimitive(motionprimitiveV);
01951
01952
01953 }
01954
01955
01956
01957 bool EnvSIPPLattice::IsValidCell(int X, int Y)
01958 {
01959 return (X >= 0 && X < envSIPPLatCfg.EnvWidth_c &&
01960 Y >= 0 && Y < envSIPPLatCfg.EnvHeight_c &&
01961 envSIPPLatCfg.Grid2D[X][Y] < envSIPPLatCfg.obsthresh);
01962 }
01963
01964 bool EnvSIPPLattice::IsWithinMapCell(int X, int Y)
01965 {
01966 return (X >= 0 && X < envSIPPLatCfg.EnvWidth_c &&
01967 Y >= 0 && Y < envSIPPLatCfg.EnvHeight_c);
01968 }
01969
01970 bool EnvSIPPLattice::IsValidConfiguration(int X, int Y, int Theta)
01971 {
01972 vector<SBPL_4Dcell_t> footprint;
01973 SBPL_4Dpt_t pose;
01974
01975
01976 pose.x = DISCXY2CONT(X, envSIPPLatCfg.cellsize_m);
01977 pose.y = DISCXY2CONT(Y, envSIPPLatCfg.cellsize_m);
01978 pose.theta = DiscTheta2Cont(Theta, ENVSIPPLAT_THETADIRS);
01979
01980
01981 CalculateFootprintForPose(pose, &footprint);
01982
01983
01984 for(int find = 0; find < (int)footprint.size(); find++)
01985 {
01986 int x = footprint.at(find).x;
01987 int y = footprint.at(find).y;
01988
01989 if (x < 0 || x >= envSIPPLatCfg.EnvWidth_c ||
01990 y < 0 || Y >= envSIPPLatCfg.EnvHeight_c ||
01991 envSIPPLatCfg.Grid2D[x][y] >= envSIPPLatCfg.obsthresh)
01992 {
01993 return false;
01994 }
01995 }
01996
01997 return true;
01998 }
01999
02000
02001 int EnvSIPPLattice::GetActionCost(int SourceX, int SourceY, int SourceTheta, envSIPPLatAction_t* action)
02002 {
02003 SBPL_4Dcell_t cell;
02004 SBPL_4Dcell_t interm4Dcell;
02005 int i;
02006
02007
02008
02009 if(!IsValidCell(SourceX, SourceY))
02010 return INFINITECOST;
02011 if(!IsValidCell(SourceX + action->dX, SourceY + action->dY))
02012 return INFINITECOST;
02013
02014
02015
02016
02017
02018 unsigned char maxcellcost = 0;
02019 for(i = 0; i < (int)action->interm4DcellsV.size(); i++)
02020 {
02021 interm4Dcell = action->interm4DcellsV.at(i);
02022 interm4Dcell.x = interm4Dcell.x + SourceX;
02023 interm4Dcell.y = interm4Dcell.y + SourceY;
02024
02025 if(interm4Dcell.x < 0 || interm4Dcell.x >= envSIPPLatCfg.EnvWidth_c ||
02026 interm4Dcell.y < 0 || interm4Dcell.y >= envSIPPLatCfg.EnvHeight_c)
02027 return INFINITECOST;
02028
02029 maxcellcost = __max(maxcellcost, envSIPPLatCfg.Grid2D[interm4Dcell.x][interm4Dcell.y]);
02030
02031 if(maxcellcost >= envSIPPLatCfg.cost_inscribed_thresh)
02032 return INFINITECOST;
02033 }
02034
02035
02036
02037
02038
02039
02040
02041
02042
02043 if(envSIPPLatCfg.FootprintPolygon.size() > 1 && (int)maxcellcost >= envSIPPLatCfg.cost_possibly_circumscribed_thresh)
02044 {
02045 checks++;
02046
02047 for(i = 0; i < (int)action->intersectingcellsV.size(); i++)
02048 {
02049
02050 cell = action->intersectingcellsV.at(i);
02051 cell.x = cell.x + SourceX;
02052 cell.y = cell.y + SourceY;
02053
02054
02055 if(!IsValidCell(cell.x, cell.y)) {
02056
02057
02058
02059
02060
02061
02062
02063
02064
02065
02066 return INFINITECOST;
02067 }
02068
02069
02070
02071 }
02072 }
02073
02074
02075
02076
02077
02078
02079
02080
02081 return action->cost;
02082
02083 }
02084
02085 double EnvSIPPLattice::EuclideanDistance_m(int X1, int Y1, int X2, int Y2)
02086 {
02087 int sqdist = ((X1-X2)*(X1-X2)+(Y1-Y2)*(Y1-Y2));
02088 return envSIPPLatCfg.cellsize_m*sqrt((double)sqdist);
02089
02090 }
02091
02092
02093
02094 void EnvSIPPLattice::CalculateFootprintForPose(SBPL_4Dpt_t pose, vector<SBPL_4Dcell_t>* footprint)
02095 {
02096 int pind;
02097
02098 #if DEBUG
02099
02100
02101 #endif
02102
02103
02104 if(envSIPPLatCfg.FootprintPolygon.size() <= 1){
02105 SBPL_4Dcell_t cell;
02106 cell.x = CONTXY2DISC(pose.x, envSIPPLatCfg.cellsize_m);
02107 cell.y = CONTXY2DISC(pose.y, envSIPPLatCfg.cellsize_m);
02108
02109 for(pind = 0; pind < (int)footprint->size(); pind++)
02110 {
02111 if(cell.x == footprint->at(pind).x && cell.y == footprint->at(pind).y)
02112 break;
02113 }
02114 if(pind == (int)footprint->size()) footprint->push_back(cell);
02115 return;
02116 }
02117
02118 vector<sbpl_2Dpt_t> bounding_polygon;
02119 unsigned int find;
02120 double max_x = -INFINITECOST, min_x = INFINITECOST, max_y = -INFINITECOST, min_y = INFINITECOST;
02121 sbpl_2Dpt_t pt = {0,0};
02122 for(find = 0; find < envSIPPLatCfg.FootprintPolygon.size(); find++){
02123
02124
02125 pt = envSIPPLatCfg.FootprintPolygon[find];
02126
02127
02128 sbpl_2Dpt_t corner;
02129 corner.x = cos(pose.theta)*pt.x - sin(pose.theta)*pt.y + pose.x;
02130 corner.y = sin(pose.theta)*pt.x + cos(pose.theta)*pt.y + pose.y;
02131 bounding_polygon.push_back(corner);
02132 #if DEBUG
02133
02134 #endif
02135 if(corner.x < min_x || find==0){
02136 min_x = corner.x;
02137 }
02138 if(corner.x > max_x || find==0){
02139 max_x = corner.x;
02140 }
02141 if(corner.y < min_y || find==0){
02142 min_y = corner.y;
02143 }
02144 if(corner.y > max_y || find==0){
02145 max_y = corner.y;
02146 }
02147
02148 }
02149
02150 #if DEBUG
02151
02152 #endif
02153
02154 int prev_discrete_x = CONTXY2DISC(pt.x, envSIPPLatCfg.cellsize_m) + 1;
02155 int prev_discrete_y = CONTXY2DISC(pt.y, envSIPPLatCfg.cellsize_m) + 1;
02156 int prev_inside = 0;
02157 int discrete_x;
02158 int discrete_y;
02159
02160 for(double x=min_x; x<=max_x; x+=envSIPPLatCfg.cellsize_m/3){
02161 for(double y=min_y; y<=max_y; y+=envSIPPLatCfg.cellsize_m/3){
02162 pt.x = x;
02163 pt.y = y;
02164 discrete_x = CONTXY2DISC(pt.x, envSIPPLatCfg.cellsize_m);
02165 discrete_y = CONTXY2DISC(pt.y, envSIPPLatCfg.cellsize_m);
02166
02167
02168 if(discrete_x != prev_discrete_x || discrete_y != prev_discrete_y || prev_inside==0){
02169
02170 #if DEBUG
02171
02172 #endif
02173
02174 if(IsInsideFootprint(pt, &bounding_polygon)){
02175
02176
02177 #if DEBUG
02178
02179 #endif
02180
02181 SBPL_4Dcell_t cell;
02182 cell.x = discrete_x;
02183 cell.y = discrete_y;
02184
02185
02186 int pind = 0;
02187 for(pind = 0; pind < (int)footprint->size(); pind++)
02188 {
02189 if(cell.x == footprint->at(pind).x && cell.y == footprint->at(pind).y)
02190 break;
02191 }
02192 if(pind == (int)footprint->size()) footprint->push_back(cell);
02193
02194 prev_inside = 1;
02195
02196 #if DEBUG
02197
02198 #endif
02199 }
02200 else{
02201 prev_inside = 0;
02202 }
02203
02204 }
02205 else
02206 {
02207 #if DEBUG
02208
02209 #endif
02210 }
02211
02212 prev_discrete_x = discrete_x;
02213 prev_discrete_y = discrete_y;
02214
02215 }
02216 }
02217 }
02218
02219
02220 void EnvSIPPLattice::RemoveSourceFootprint(SBPL_4Dpt_t sourcepose, vector<SBPL_4Dcell_t>* footprint)
02221 {
02222 vector<SBPL_4Dcell_t> sourcefootprint;
02223
02224
02225 CalculateFootprintForPose(sourcepose, &sourcefootprint);
02226
02227
02228 for(int sind = 0; sind < (int)sourcefootprint.size(); sind++)
02229 {
02230 for(int find = 0; find < (int)footprint->size(); find++)
02231 {
02232 if(sourcefootprint.at(sind).x == footprint->at(find).x && sourcefootprint.at(sind).y == footprint->at(find).y)
02233 {
02234 footprint->erase(footprint->begin() + find);
02235 break;
02236 }
02237 }
02238 }
02239
02240
02241
02242 }
02243
02244
02245
02246
02247
02248
02249 void EnvSIPPLattice::ComputeHeuristicValues()
02250 {
02251
02252 SBPL_PRINTF("Precomputing heuristics...\n");
02253
02254
02255 grid2Dsearchfromstart = new SBPL2DGridSearch(envSIPPLatCfg.EnvWidth_c, envSIPPLatCfg.EnvHeight_c, (float)envSIPPLatCfg.cellsize_m);
02256 grid2Dsearchfromgoal = new SBPL2DGridSearch(envSIPPLatCfg.EnvWidth_c, envSIPPLatCfg.EnvHeight_c, (float)envSIPPLatCfg.cellsize_m);
02257
02258 SBPL_PRINTF("done\n");
02259
02260 }
02261
02262
02263 bool EnvSIPPLattice::CheckQuant(FILE* fOut)
02264 {
02265
02266 for(double theta = -10; theta < 10; theta += 2.0*PI_CONST/ENVSIPPLAT_THETADIRS*0.01)
02267 {
02268 int nTheta = ContTheta2Disc(theta, ENVSIPPLAT_THETADIRS);
02269 double newTheta = DiscTheta2Cont(nTheta, ENVSIPPLAT_THETADIRS);
02270 int nnewTheta = ContTheta2Disc(newTheta, ENVSIPPLAT_THETADIRS);
02271
02272 SBPL_FPRINTF(fOut, "theta=%f(%f)->%d->%f->%d\n", theta, theta*180/PI_CONST, nTheta, newTheta, nnewTheta);
02273
02274 if(nTheta != nnewTheta)
02275 {
02276 SBPL_ERROR("ERROR: invalid quantization\n");
02277 return false;
02278 }
02279 }
02280
02281 return true;
02282 }
02283
02284
02285
02286
02287
02288
02289 bool EnvSIPPLattice::InitializeEnv(const char* sEnvFile, const vector<sbpl_2Dpt_t>& perimeterptsV, const char* sMotPrimFile, const char* sDynObsFile){
02290
02291 InitializeEnv(sEnvFile, perimeterptsV, sMotPrimFile);
02292
02293
02294 FILE* fDynObs = fopen(sDynObsFile, "r");
02295 if(fDynObs == NULL){
02296 SBPL_PRINTF("Error: unable to open %s\n", sDynObsFile);
02297 throw new SBPL_Exception();
02298 }
02299 ReadDynamicObstacles(fDynObs);
02300 fclose(fDynObs);
02301 return UpdateTimelineMap();
02302 }
02303
02304 bool EnvSIPPLattice::InitializeEnv(const char* sEnvFile, const vector<sbpl_2Dpt_t>& perimeterptsV, const char* sMotPrimFile)
02305 {
02306
02307
02308 double max_sqr_radius = 0;
02309 for(unsigned int i=0; i<perimeterptsV.size(); i++){
02310 double x = perimeterptsV.at(i).x;
02311 double y = perimeterptsV.at(i).y;
02312 double d = x*x + y*y;
02313 if(d > max_sqr_radius)
02314 max_sqr_radius = d;
02315 }
02316 envSIPPLatCfg.robotRadius = sqrt(max_sqr_radius);
02317 SBPL_PRINTF("robotRadius=%f\n", envSIPPLatCfg.robotRadius);
02318
02319 envSIPPLatCfg.FootprintPolygon = perimeterptsV;
02320
02321 FILE* fCfg = fopen(sEnvFile, "r");
02322 if(fCfg == NULL)
02323 {
02324 SBPL_ERROR("ERROR: unable to open %s\n", sEnvFile);
02325 throw new SBPL_Exception();
02326 }
02327 ReadConfiguration(fCfg);
02328 fclose(fCfg);
02329
02330 temporal_padding = DEFAULT_TEMPORAL_PADDING;
02331 InitializeTimelineMap();
02332
02333 if(sMotPrimFile != NULL)
02334 {
02335 FILE* fMotPrim = fopen(sMotPrimFile, "r");
02336 if(fMotPrim == NULL)
02337 {
02338 SBPL_ERROR("ERROR: unable to open %s\n", sMotPrimFile);
02339 throw new SBPL_Exception();
02340 }
02341 if(ReadMotionPrimitives(fMotPrim) == false)
02342 {
02343 SBPL_ERROR("ERROR: failed to read in motion primitive file\n");
02344 throw new SBPL_Exception();
02345 }
02346 fclose(fMotPrim);
02347 InitGeneral(&envSIPPLatCfg.mprimV);
02348 }
02349 else
02350 InitGeneral(NULL);
02351
02352 return true;
02353 }
02354
02355
02356 bool EnvSIPPLattice::InitializeEnv(const char* sEnvFile)
02357 {
02358
02359 FILE* fCfg = fopen(sEnvFile, "r");
02360 if(fCfg == NULL)
02361 {
02362 SBPL_ERROR("ERROR: unable to open %s\n", sEnvFile);
02363 throw new SBPL_Exception();
02364 }
02365 ReadConfiguration(fCfg);
02366 fclose(fCfg);
02367
02368 InitGeneral(NULL);
02369
02370
02371 return true;
02372 }
02373
02374 bool EnvSIPPLattice::InitializeEnv(int width, int height,
02375 const unsigned char* mapdata,
02376 double startx, double starty, double starttheta, double startTime,
02377 double goalx, double goaly, double goaltheta,
02378 double goaltol_x, double goaltol_y, double goaltol_theta,
02379 const vector<sbpl_2Dpt_t> & perimeterptsV,
02380 double cellsize_m, double timeResolution,
02381 double nominalvel_mpersecs, double timetoturn45degsinplace_secs,
02382 unsigned char obsthresh, unsigned char dynobsthresh, const char* sMotPrimFile,
02383 vector<SBPL_DynamicObstacle_t> & dynObs)
02384 {
02385
02386 SBPL_PRINTF("env: initialize with width=%d height=%d start=%.3f %.3f %.3f %.3f goalx=%.3f %.3f %.3f cellsize=%.3f timeResolution=%.3f nomvel=%.3f timetoturn=%.3f, obsthresh=%d\n",
02387 width, height, startx, starty, starttheta, startTime, goalx, goaly, goaltheta, cellsize_m, timeResolution, nominalvel_mpersecs, timetoturn45degsinplace_secs, obsthresh);
02388
02389 SBPL_PRINTF("perimeter has size=%d\n", (int)perimeterptsV.size());
02390
02391 for(int i = 0; i < (int)perimeterptsV.size(); i++)
02392 {
02393 SBPL_PRINTF("perimeter(%d) = %.4f %.4f\n", i, perimeterptsV.at(i).x, perimeterptsV.at(i).y);
02394 }
02395
02396
02397 envSIPPLatCfg.obsthresh = obsthresh;
02398 envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh = dynobsthresh;
02399
02400
02401 double max_sqr_radius = 0;
02402 for(unsigned int i=0; i<perimeterptsV.size(); i++){
02403 double x = perimeterptsV.at(i).x;
02404 double y = perimeterptsV.at(i).y;
02405 double d = x*x + y*y;
02406 if(d > max_sqr_radius)
02407 max_sqr_radius = d;
02408 }
02409 envSIPPLatCfg.robotRadius = sqrt(max_sqr_radius);
02410 dynamicObstacles.clear();
02411 for(unsigned int i=0; i<dynObs.size(); i++){
02412 SBPL_DynamicObstacle_t obs;
02413 obs.radius = dynObs[i].radius + envSIPPLatCfg.robotRadius;
02414 for(unsigned int j=0; j<dynObs[i].trajectories.size(); j++){
02415 SBPL_Trajectory_t traj;
02416 traj.prob = dynObs[i].trajectories[j].prob;
02417 traj.existsAfter = dynObs[i].trajectories[j].existsAfter;
02418 for(unsigned int k=0; k<dynObs[i].trajectories[j].points.size(); k++){
02419 SBPL_Traj_Pt_t p;
02420 p.x = dynObs[i].trajectories[j].points[k].x;
02421 p.y = dynObs[i].trajectories[j].points[k].y;
02422 p.t = dynObs[i].trajectories[j].points[k].t;
02423 p.std_dev = dynObs[i].trajectories[j].points[k].std_dev;
02424 traj.points.push_back(p);
02425 }
02426 obs.trajectories.push_back(traj);
02427 }
02428 dynamicObstacles.push_back(obs);
02429 }
02430
02431
02432
02433 SetConfiguration(width, height,
02434 mapdata,
02435 CONTXY2DISC(startx, cellsize_m), CONTXY2DISC(starty, cellsize_m), ContTheta2Disc(starttheta, ENVSIPPLAT_THETADIRS), CONTTIME2DISC(startTime, timeResolution),
02436 CONTXY2DISC(goalx, cellsize_m), CONTXY2DISC(goaly, cellsize_m), ContTheta2Disc(goaltheta, ENVSIPPLAT_THETADIRS),
02437 cellsize_m, timeResolution, nominalvel_mpersecs, timetoturn45degsinplace_secs, perimeterptsV);
02438
02439 if(sMotPrimFile != NULL)
02440 {
02441 FILE* fMotPrim = fopen(sMotPrimFile, "r");
02442 if(fMotPrim == NULL)
02443 {
02444 SBPL_ERROR("ERROR: unable to open %s\n", sMotPrimFile);
02445 throw new SBPL_Exception();
02446 }
02447
02448 if(ReadMotionPrimitives(fMotPrim) == false)
02449 {
02450 SBPL_ERROR("ERROR: failed to read in motion primitive file\n");
02451 throw new SBPL_Exception();
02452 }
02453 fclose(fMotPrim);
02454 }
02455
02456 temporal_padding = DEFAULT_TEMPORAL_PADDING;
02457 InitializeTimelineMap();
02458
02459 if(envSIPPLatCfg.mprimV.size() != 0)
02460 {
02461 InitGeneral(&envSIPPLatCfg.mprimV);
02462 }
02463 else
02464 InitGeneral(NULL);
02465
02466 return true;
02467 }
02468
02469
02470 bool EnvSIPPLattice::InitializeEnv(int width, int height,
02471 const unsigned char* mapdata,
02472 double startx, double starty, double starttheta, double startTime,
02473 double goalx, double goaly, double goaltheta,
02474 double goaltol_x, double goaltol_y, double goaltol_theta,
02475 const vector<sbpl_2Dpt_t> & perimeterptsV,
02476 double cellsize_m, double timeResolution,
02477 double nominalvel_mpersecs, double timetoturn45degsinplace_secs,
02478 unsigned char obsthresh, unsigned char dynobsthresh, const char* sMotPrimFile)
02479 {
02480
02481 SBPL_PRINTF("env: initialize with width=%d height=%d start=%.3f %.3f %.3f %.3f goalx=%.3f %.3f %.3f cellsize=%.3f timeResolution=%.3f nomvel=%.3f timetoturn=%.3f, obsthresh=%d\n",
02482 width, height, startx, starty, starttheta, startTime, goalx, goaly, goaltheta, cellsize_m, timeResolution, nominalvel_mpersecs, timetoturn45degsinplace_secs, obsthresh);
02483
02484 SBPL_PRINTF("perimeter has size=%d\n", (int)perimeterptsV.size());
02485
02486 for(int i = 0; i < (int)perimeterptsV.size(); i++)
02487 {
02488 SBPL_PRINTF("perimeter(%d) = %.4f %.4f\n", i, perimeterptsV.at(i).x, perimeterptsV.at(i).y);
02489 }
02490
02491
02492 envSIPPLatCfg.obsthresh = obsthresh;
02493 envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh = dynobsthresh;
02494
02495
02496
02497 SetConfiguration(width, height,
02498 mapdata,
02499 CONTXY2DISC(startx, cellsize_m), CONTXY2DISC(starty, cellsize_m), ContTheta2Disc(starttheta, ENVSIPPLAT_THETADIRS), CONTTIME2DISC(startTime, timeResolution),
02500 CONTXY2DISC(goalx, cellsize_m), CONTXY2DISC(goaly, cellsize_m), ContTheta2Disc(goaltheta, ENVSIPPLAT_THETADIRS),
02501 cellsize_m, timeResolution, nominalvel_mpersecs, timetoturn45degsinplace_secs, perimeterptsV);
02502
02503 if(sMotPrimFile != NULL)
02504 {
02505 FILE* fMotPrim = fopen(sMotPrimFile, "r");
02506 if(fMotPrim == NULL)
02507 {
02508 SBPL_ERROR("ERROR: unable to open %s\n", sMotPrimFile);
02509 throw new SBPL_Exception();
02510 }
02511
02512 if(ReadMotionPrimitives(fMotPrim) == false)
02513 {
02514 SBPL_ERROR("ERROR: failed to read in motion primitive file\n");
02515 throw new SBPL_Exception();
02516 }
02517 fclose(fMotPrim);
02518 }
02519
02520 if(envSIPPLatCfg.mprimV.size() != 0)
02521 {
02522 InitGeneral(&envSIPPLatCfg.mprimV);
02523 }
02524 else
02525 InitGeneral(NULL);
02526
02527 return true;
02528 }
02529
02530
02531 bool EnvSIPPLattice::InitGeneral(vector<SBPL_xythetasipp_mprimitive>* motionprimitiveV) {
02532
02533
02534
02535 InitializeEnvConfig(motionprimitiveV);
02536
02537
02538 InitializeEnvironment();
02539
02540
02541 ComputeHeuristicValues();
02542
02543 return true;
02544 }
02545
02546 bool EnvSIPPLattice::InitializeMDPCfg(MDPConfig *MDPCfg)
02547 {
02548
02549 MDPCfg->goalstateid = envSIPPLat.goalstateid;
02550 MDPCfg->startstateid = envSIPPLat.startstateid;
02551
02552 return true;
02553 }
02554
02555
02556 void EnvSIPPLattice::PrintHeuristicValues()
02557 {
02558 FILE* fHeur = fopen("heur.txt", "w");
02559 SBPL2DGridSearch* grid2Dsearch = NULL;
02560
02561 for(int i = 0; i < 2; i++)
02562 {
02563 if(i == 0 && grid2Dsearchfromstart != NULL)
02564 {
02565 grid2Dsearch = grid2Dsearchfromstart;
02566 SBPL_FPRINTF(fHeur, "start heuristics:\n");
02567 }
02568 else if(i == 1 && grid2Dsearchfromgoal != NULL)
02569 {
02570 grid2Dsearch = grid2Dsearchfromgoal;
02571 SBPL_FPRINTF(fHeur, "goal heuristics:\n");
02572 }
02573 else
02574 continue;
02575
02576 for (int y = 0; y < envSIPPLatCfg.EnvHeight_c; y++) {
02577 for (int x = 0; x < envSIPPLatCfg.EnvWidth_c; x++) {
02578 if(grid2Dsearch->getlowerboundoncostfromstart_inmm(x, y) < INFINITECOST)
02579 SBPL_FPRINTF(fHeur, "%5d ", grid2Dsearch->getlowerboundoncostfromstart_inmm(x, y));
02580 else
02581 SBPL_FPRINTF(fHeur, "XXXXX ");
02582 }
02583 SBPL_FPRINTF(fHeur, "\n");
02584 }
02585 }
02586 fclose(fHeur);
02587 }
02588
02589
02590
02591
02592 void EnvSIPPLattice::SetAllPreds(CMDPSTATE* state)
02593 {
02594
02595
02596 SBPL_ERROR("ERROR in envSIPPLat... function: SetAllPreds is undefined\n");
02597 throw new SBPL_Exception();
02598 }
02599
02600
02601 void EnvSIPPLattice::GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV)
02602 {
02603 GetSuccs(SourceStateID, SuccIDV, CostV, NULL);
02604 }
02605
02606
02607
02608 const envSIPPLatConfig_t* EnvSIPPLattice::GetEnvNavConfig() {
02609 return &envSIPPLatCfg;
02610 }
02611
02612
02613
02614 bool EnvSIPPLattice::UpdateCost(int x, int y, unsigned char newcost)
02615 {
02616
02617 #if DEBUG
02618 SBPL_FPRINTF(fDeb, "Cost updated for cell %d %d from old cost=%d to new cost=%d\n", x,y,envSIPPLatCfg.Grid2D[x][y], newcost);
02619 #endif
02620
02621 envSIPPLatCfg.Grid2D[x][y] = newcost;
02622
02623 bNeedtoRecomputeStartHeuristics = true;
02624 bNeedtoRecomputeGoalHeuristics = true;
02625
02626 return true;
02627 }
02628
02629
02630 void EnvSIPPLattice::PrintEnv_Config(FILE* fOut)
02631 {
02632
02633
02634
02635 SBPL_ERROR("ERROR in envSIPPLat... function: PrintEnv_Config is undefined\n");
02636 throw new SBPL_Exception();
02637
02638 }
02639
02640 void EnvSIPPLattice::PrintTimeStat(FILE* fOut)
02641 {
02642
02643 #if TIME_DEBUG
02644 SBPL_FPRINTF(fOut, "time3_addallout = %f secs, time_gethash = %f secs, time_createhash = %f secs, time_getsuccs = %f\n",
02645 time3_addallout/(double)CLOCKS_PER_SEC, time_gethash/(double)CLOCKS_PER_SEC,
02646 time_createhash/(double)CLOCKS_PER_SEC, time_getsuccs/(double)CLOCKS_PER_SEC);
02647 #endif
02648 }
02649
02650
02651
02652 bool EnvSIPPLattice::IsObstacle(int x, int y)
02653 {
02654
02655 #if DEBUG
02656 SBPL_FPRINTF(fDeb, "Status of cell %d %d is queried. Its cost=%d\n", x,y,envSIPPLatCfg.Grid2D[x][y]);
02657 #endif
02658
02659
02660 return (envSIPPLatCfg.Grid2D[x][y] >= envSIPPLatCfg.obsthresh);
02661
02662 }
02663
02664 int EnvSIPPLattice::getStartID(){
02665 return envSIPPLat.startstateid;
02666 }
02667
02668 int EnvSIPPLattice::getGoalID(){
02669 return envSIPPLat.goalstateid;
02670 }
02671
02672 void EnvSIPPLattice::GetEnvParms(int *size_x, int *size_y, double* startx, double* starty, double*starttheta, double* startTime, double* goalx, double* goaly, double* goaltheta,
02673 double* cellsize_m, double* timeResolution, double* nominalvel_mpersecs, double* timetoturn45degsinplace_secs, unsigned char* obsthresh, unsigned char* dyn_obs_thresh,
02674 vector<SBPL_xythetasipp_mprimitive>* mprimitiveV)
02675 {
02676 *size_x = envSIPPLatCfg.EnvWidth_c;
02677 *size_y = envSIPPLatCfg.EnvHeight_c;
02678
02679 *startx = DISCXY2CONT(envSIPPLatCfg.StartX_c, envSIPPLatCfg.cellsize_m);
02680 *starty = DISCXY2CONT(envSIPPLatCfg.StartY_c, envSIPPLatCfg.cellsize_m);
02681 *starttheta = DiscTheta2Cont(envSIPPLatCfg.StartTheta, ENVSIPPLAT_THETADIRS);
02682 *startTime = DISCTIME2CONT(envSIPPLatCfg.StartTime, envSIPPLatCfg.timeResolution);
02683 *goalx = DISCXY2CONT(envSIPPLatCfg.EndX_c, envSIPPLatCfg.cellsize_m);
02684 *goaly = DISCXY2CONT(envSIPPLatCfg.EndY_c, envSIPPLatCfg.cellsize_m);
02685 *goaltheta = DiscTheta2Cont(envSIPPLatCfg.EndTheta, ENVSIPPLAT_THETADIRS);
02686
02687 *cellsize_m = envSIPPLatCfg.cellsize_m;
02688 *timeResolution = envSIPPLatCfg.timeResolution;
02689 *nominalvel_mpersecs = envSIPPLatCfg.nominalvel_mpersecs;
02690 *timetoturn45degsinplace_secs = envSIPPLatCfg.timetoturn45degsinplace_secs;
02691
02692 *dyn_obs_thresh = envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh;
02693 *obsthresh = envSIPPLatCfg.obsthresh;
02694
02695 *mprimitiveV = envSIPPLatCfg.mprimV;
02696 }
02697
02698 bool EnvSIPPLattice::PoseContToDisc(double px, double py, double pth, double pt,
02699 int &ix, int &iy, int &ith, int &it) const
02700 {
02701 ix = CONTXY2DISC(px, envSIPPLatCfg.cellsize_m);
02702 iy = CONTXY2DISC(py, envSIPPLatCfg.cellsize_m);
02703 ith = ContTheta2Disc(pth, ENVSIPPLAT_THETADIRS);
02704 it = CONTTIME2DISC(pt, envSIPPLatCfg.timeResolution);
02705 return (pth >= -2*PI_CONST) && (pth <= 2*PI_CONST)
02706 && (ix >= 0) && (ix < envSIPPLatCfg.EnvWidth_c)
02707 && (iy >= 0) && (iy < envSIPPLatCfg.EnvHeight_c);
02708 }
02709
02710 bool EnvSIPPLattice::PoseDiscToCont(int ix, int iy, int ith, int it,
02711 double &px, double &py, double &pth, double &pt) const
02712 {
02713 px = DISCXY2CONT(ix, envSIPPLatCfg.cellsize_m);
02714 py = DISCXY2CONT(iy, envSIPPLatCfg.cellsize_m);
02715 pth = normalizeAngle(DiscTheta2Cont(ith, ENVSIPPLAT_THETADIRS));
02716 pt = DISCTIME2CONT(it, envSIPPLatCfg.timeResolution);
02717 return (ith >= 0) && (ith < ENVSIPPLAT_THETADIRS)
02718 && (ix >= 0) && (ix < envSIPPLatCfg.EnvWidth_c)
02719 && (iy >= 0) && (iy < envSIPPLatCfg.EnvHeight_c);
02720 }
02721
02722 unsigned char EnvSIPPLattice::GetMapCost(int x, int y)
02723 {
02724 return envSIPPLatCfg.Grid2D[x][y];
02725 }
02726
02727
02728
02729 bool EnvSIPPLattice::SetEnvParameter(const char* parameter, int value)
02730 {
02731
02732 if(envSIPPLat.bInitialized == true)
02733 {
02734 SBPL_ERROR("ERROR: all parameters must be set before initialization of the environment\n");
02735 return false;
02736 }
02737
02738 SBPL_PRINTF("setting parameter %s to %d\n", parameter, value);
02739
02740 if(strcmp(parameter, "cost_inscribed_thresh") == 0)
02741 {
02742 if(value < 0 || value > 255)
02743 {
02744 SBPL_ERROR("ERROR: invalid value %d for parameter %s\n", value, parameter);
02745 return false;
02746 }
02747 envSIPPLatCfg.cost_inscribed_thresh = (unsigned char)value;
02748 }
02749 else if(strcmp(parameter, "cost_possibly_circumscribed_thresh") == 0)
02750 {
02751 if(value < 0 || value > 255)
02752 {
02753 SBPL_ERROR("ERROR: invalid value %d for parameter %s\n", value, parameter);
02754 return false;
02755 }
02756 envSIPPLatCfg.cost_possibly_circumscribed_thresh = value;
02757 }
02758 else if(strcmp(parameter, "cost_obsthresh") == 0)
02759 {
02760 if(value < 0 || value > 255)
02761 {
02762 SBPL_ERROR("ERROR: invalid value %d for parameter %s\n", value, parameter);
02763 return false;
02764 }
02765 envSIPPLatCfg.obsthresh = (unsigned char)value;
02766 }
02767 else if(strcmp(parameter, "cost_dyn_obs_thresh") == 0)
02768 {
02769 if(value < 0 || value > 255)
02770 {
02771 SBPL_ERROR("ERROR: invalid value %d for parameter %s\n", value, parameter);
02772 return false;
02773 }
02774 envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh = (unsigned char)value;
02775 }
02776 else
02777 {
02778 SBPL_ERROR("ERROR: invalid parameter %s\n", parameter);
02779 return false;
02780 }
02781
02782 return true;
02783 }
02784
02785 int EnvSIPPLattice::GetEnvParameter(const char* parameter)
02786 {
02787
02788 if(strcmp(parameter, "cost_inscribed_thresh") == 0)
02789 {
02790 return (int) envSIPPLatCfg.cost_inscribed_thresh;
02791 }
02792 else if(strcmp(parameter, "cost_possibly_circumscribed_thresh") == 0)
02793 {
02794 return (int) envSIPPLatCfg.cost_possibly_circumscribed_thresh;
02795 }
02796 else if(strcmp(parameter, "cost_obsthresh") == 0)
02797 {
02798 return (int) envSIPPLatCfg.obsthresh;
02799 }
02800 else if(strcmp(parameter, "cost_dyn_obs_thresh") == 0)
02801 {
02802 return (int) envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh;
02803 }
02804 else
02805 {
02806 SBPL_ERROR("ERROR: invalid parameter %s\n", parameter);
02807 throw new SBPL_Exception();
02808 }
02809
02810 }
02811
02812
02813
02814
02815
02816
02817 void EnvSIPPLat::GetCoordFromState(int stateID, int& x, int& y, int& theta, int& t) const {
02818 envSIPPLatHashEntry_t* HashEntry = StateID2CoordTable[stateID];
02819 x = HashEntry->X;
02820 y = HashEntry->Y;
02821 theta = HashEntry->Theta;
02822 t = HashEntry->T;
02823 }
02824
02825 int EnvSIPPLat::GetStateFromCoord(int x, int y, int theta, int t){
02826 SBPL_PRINTF("Error: GetStateFromCoord shouldn't be used right now...\n");
02827
02828
02829 envSIPPLatHashEntry_t* OutHashEntry;
02830 if((OutHashEntry = GetHashEntry(x, y, theta, getInterval(x,y,t), t)) == NULL){
02831
02832 OutHashEntry = CreateNewHashEntry(x, y, theta, getInterval(x,y,t), t);
02833 }
02834 SBPL_PRINTF("interval = %d\n",getInterval(x,y,t));
02835 for(unsigned int i=0; i<timelineMap[x][y].size(); i++)
02836 SBPL_PRINTF("%d ",timelineMap[x][y][i]);
02837 SBPL_PRINTF("\n");
02838 return OutHashEntry->stateID;
02839 }
02840
02841 void EnvSIPPLat::ConvertStateIDPathintoXYThetaPath(vector<int>* stateIDPath, vector<SBPL_4Dpt_t>* xythetaPath)
02842 {
02843 vector<envSIPPLatAction_t*> actionV;
02844 vector<int> CostV;
02845 vector<int> SuccIDV;
02846 int targetx_c, targety_c, targettheta_c;
02847 int sourcex_c, sourcey_c, sourcetheta_c;
02848 int targett_c, sourcet_c;
02849
02850
02851
02852 xythetaPath->clear();
02853
02854 #if DEBUG
02855 SBPL_FPRINTF(fDeb, "converting stateid path into coordinates:\n");
02856 #endif
02857
02858 for(int pind = 0; pind < (int)(stateIDPath->size())-1; pind++)
02859 {
02860 int sourceID = stateIDPath->at(pind);
02861
02862
02863 int targetID = stateIDPath->at(pind+1);
02864
02865 #if DEBUG
02866 GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcet_c);
02867 #endif
02868
02869
02870
02871 SuccIDV.clear();
02872 CostV.clear();
02873 actionV.clear();
02874 GetSuccs(sourceID, &SuccIDV, &CostV, &actionV);
02875
02876 int bestcost = INFINITECOST;
02877 int bestsind = -1;
02878
02879 #if DEBUG
02880 GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcet_c);
02881 GetCoordFromState(targetID, targetx_c, targety_c, targettheta_c, targett_c);
02882 SBPL_FPRINTF(fDeb, "looking for %d %d %d %d -> %d %d %d %d (numofsuccs=%d)\n", sourcex_c, sourcey_c, sourcetheta_c, sourcet_c
02883 targetx_c, targety_c, targettheta_c, targett_c, SuccIDV.size());
02884
02885 #endif
02886
02887
02888 for(int sind = 0; sind < (int)SuccIDV.size(); sind++)
02889 {
02890
02891 #if DEBUG
02892 int x_c, y_c, theta_c, t_c;
02893 GetCoordFromState(SuccIDV[sind], x_c, y_c, theta_c, t_c);
02894 SBPL_FPRINTF(fDeb, "succ: %d %d %d %d\n", x_c, y_c, theta_c, t_c);
02895 #endif
02896
02897 if(SuccIDV[sind] == targetID && CostV[sind] <= bestcost)
02898 {
02899 bestcost = CostV[sind];
02900 bestsind = sind;
02901 }
02902 }
02903 if(bestsind == -1)
02904 {
02905 SBPL_ERROR("ERROR: successor not found for transition:\n");
02906 GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcet_c);
02907 GetCoordFromState(targetID, targetx_c, targety_c, targettheta_c, targett_c);
02908 SBPL_PRINTF("ID=%d %d %d %d %d -> ID=%d %d %d %d %d\n", sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcet_c,
02909 targetID, targetx_c, targety_c, targettheta_c, targett_c);
02910 throw new SBPL_Exception();
02911 }
02912
02913
02914 int sourcex_c, sourcey_c, sourcetheta_c, sourcet_c;
02915 int targetx_c, targety_c, targettheta_c, targett_c;
02916 GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcet_c);
02917 GetCoordFromState(targetID, targetx_c, targety_c, targettheta_c, targett_c);
02918 double sourcex, sourcey, sourcet;
02919 sourcex = DISCXY2CONT(sourcex_c, envSIPPLatCfg.cellsize_m);
02920 sourcey = DISCXY2CONT(sourcey_c, envSIPPLatCfg.cellsize_m);
02921
02922 if(targett_c - sourcet_c > actionV[bestsind]->dT){
02923 SBPL_4Dpt_t intermpt = actionV[bestsind]->intermptV[0];
02924 intermpt.x += sourcex;
02925 intermpt.y += sourcey;
02926 intermpt.t = DISCTIME2CONT(sourcet_c, envSIPPLatCfg.timeResolution);
02927 xythetaPath->push_back(intermpt);
02928 sourcet = DISCTIME2CONT(targett_c-actionV[bestsind]->dT, envSIPPLatCfg.timeResolution);
02929
02930 SBPL_PRINTF("post-process wait %d\n", targett_c-sourcet_c-actionV[bestsind]->dT);
02931 }
02932 else
02933 sourcet = DISCTIME2CONT(sourcet_c, envSIPPLatCfg.timeResolution);
02934
02935
02936 for(int ipind = 0; ipind < ((int)actionV[bestsind]->intermptV.size())-1; ipind++)
02937 {
02938
02939 SBPL_4Dpt_t intermpt = actionV[bestsind]->intermptV[ipind];
02940 intermpt.x += sourcex;
02941 intermpt.y += sourcey;
02942 intermpt.t += sourcet;
02943
02944 #if DEBUG
02945 int nx = CONTXY2DISC(intermpt.x, envSIPPLatCfg.cellsize_m);
02946 int ny = CONTXY2DISC(intermpt.y, envSIPPLatCfg.cellsize_m);
02947 int nt = CONTTIME2DISC(intermpt.t, envSIPPLatCfg.timeResolution);
02948 SBPL_FPRINTF(fDeb, "%.3f %.3f %.3f %.3f (%d %d %d cost=%d) ",
02949 intermpt.x, intermpt.y, intermpt.theta, intermpt.t
02950 nx, ny,
02951 ContTheta2Disc(intermpt.theta, ENVSIPPLAT_THETADIRS), nt, envSIPPLatCfg.Grid2D[nx][ny]);
02952 if(ipind == 0) SBPL_FPRINTF(fDeb, "first (heur=%d)\n", GetStartHeuristic(sourceID));
02953 else SBPL_FPRINTF(fDeb, "\n");
02954 #endif
02955
02956
02957 xythetaPath->push_back(intermpt);
02958 }
02959 }
02960 }
02961
02962
02963
02964 int EnvSIPPLat::SetGoal(double x_m, double y_m, double theta_rad){
02965
02966 int x = CONTXY2DISC(x_m, envSIPPLatCfg.cellsize_m);
02967 int y = CONTXY2DISC(y_m, envSIPPLatCfg.cellsize_m);
02968 int theta = ContTheta2Disc(theta_rad, ENVSIPPLAT_THETADIRS);
02969
02970 SBPL_PRINTF("env: setting goal to %.3f %.3f %.3f (%d %d %d)\n", x_m, y_m, theta_rad, x, y, theta);
02971
02972 if(!IsWithinMapCell(x,y))
02973 {
02974 SBPL_ERROR("ERROR: trying to set a goal cell %d %d that is outside of map\n", x,y);
02975 return -1;
02976 }
02977
02978 if(!IsValidConfiguration(x,y,theta))
02979 {
02980 SBPL_PRINTF("WARNING: goal configuration is invalid\n");
02981 }
02982
02983 envSIPPLatHashEntry_t* OutHashEntry;
02984 if((OutHashEntry = GetHashEntry(x, y, theta, INFINITECOST, INFINITECOST)) == NULL){
02985
02986 OutHashEntry = CreateNewHashEntry(x, y, theta, INFINITECOST, INFINITECOST);
02987 }
02988
02989
02990
02991 int oldGoalX, oldGoalY, oldGoalTheta;
02992 int oldGoalT;
02993 GetCoordFromState(envSIPPLat.goalstateid, oldGoalX, oldGoalY, oldGoalTheta, oldGoalT);
02994 if(oldGoalX != x || oldGoalY != y || oldGoalTheta != theta)
02995 {
02996 bNeedtoRecomputeStartHeuristics = true;
02997 bNeedtoRecomputeGoalHeuristics = true;
02998 }
02999
03000
03001
03002 envSIPPLat.goalstateid = OutHashEntry->stateID;
03003
03004 envSIPPLatCfg.EndX_c = x;
03005 envSIPPLatCfg.EndY_c = y;
03006 envSIPPLatCfg.EndTheta = theta;
03007
03008
03009
03010
03011
03012
03013
03014 return envSIPPLat.goalstateid;
03015
03016 }
03017
03018
03019
03020 int EnvSIPPLat::SetStart(double x_m, double y_m, double theta_rad, double startTime){
03021
03022 int x = CONTXY2DISC(x_m, envSIPPLatCfg.cellsize_m);
03023 int y = CONTXY2DISC(y_m, envSIPPLatCfg.cellsize_m);
03024 int theta = ContTheta2Disc(theta_rad, ENVSIPPLAT_THETADIRS);
03025 int t = CONTTIME2DISC(startTime, envSIPPLatCfg.timeResolution);
03026
03027 if(!IsWithinMapCell(x,y))
03028 {
03029 SBPL_ERROR("ERROR: trying to set a start cell %d %d that is outside of map\n", x,y);
03030 return -1;
03031 }
03032
03033 SBPL_PRINTF("env: setting start to %.3f %.3f %.3f %.3f (%d %d %d %d)\n", x_m, y_m, theta_rad, startTime, x, y, theta, t);
03034
03035 if(!IsValidConfiguration(x,y,theta) || getInterval(x,y,t) < 0)
03036 {
03037 SBPL_PRINTF("WARNING: start configuration x=%d y=%d th=%d t=%d i=%d is invalid\n", x,y,theta,t,getInterval(x,y,t));
03038 return false;
03039 }
03040
03041 envSIPPLatHashEntry_t* OutHashEntry;
03042 if((OutHashEntry = GetHashEntry(x, y, theta, getInterval(x,y,t), t)) == NULL){
03043
03044 OutHashEntry = CreateNewHashEntry(x, y, theta, getInterval(x,y,t), t);
03045 }
03046
03047
03048
03049 int oldStartX, oldStartY, oldStartTheta;
03050 int oldStartT;
03051 GetCoordFromState(envSIPPLat.startstateid, oldStartX, oldStartY, oldStartTheta, oldStartT);
03052 if(oldStartX != x || oldStartY != y || oldStartTheta != theta)
03053 {
03054 bNeedtoRecomputeStartHeuristics = true;
03055 bNeedtoRecomputeGoalHeuristics = true;
03056 }
03057
03058
03059 envSIPPLat.startstateid = OutHashEntry->stateID;
03060 envSIPPLatCfg.StartX_c = x;
03061 envSIPPLatCfg.StartY_c = y;
03062 envSIPPLatCfg.StartTheta = theta;
03063 envSIPPLatCfg.StartTime = t;
03064
03065 return envSIPPLat.startstateid;
03066
03067 }
03068
03069 bool EnvSIPPLat::setDynamicObstacles(vector<SBPL_DynamicObstacle_t> dynObs, bool reset_states ){
03070 dynamicObstacles.clear();
03071 for(unsigned int i=0; i<dynObs.size(); i++){
03072 SBPL_DynamicObstacle_t obs;
03073 obs.radius = dynObs[i].radius + envSIPPLatCfg.robotRadius;
03074 for(unsigned int j=0; j<dynObs[i].trajectories.size(); j++){
03075 SBPL_Trajectory_t traj;
03076 traj.prob = dynObs[i].trajectories[j].prob;
03077 traj.existsAfter = dynObs[i].trajectories[j].existsAfter;
03078 for(unsigned int k=0; k<dynObs[i].trajectories[j].points.size(); k++){
03079 SBPL_Traj_Pt_t p;
03080 p.x = dynObs[i].trajectories[j].points[k].x;
03081 p.y = dynObs[i].trajectories[j].points[k].y;
03082 p.t = dynObs[i].trajectories[j].points[k].t;
03083 p.std_dev = dynObs[i].trajectories[j].points[k].std_dev;
03084 traj.points.push_back(p);
03085
03086 }
03087 obs.trajectories.push_back(traj);
03088 }
03089 dynamicObstacles.push_back(obs);
03090 }
03091 SBPL_PRINTF("we have %d dynamic obstacles\n", (int)dynamicObstacles.size());
03092
03093
03094
03095
03096 bool ret = UpdateTimelineMap();
03097 if(reset_states){
03098 ClearStates();
03099 return true;
03100 }
03101 return ret;
03102 }
03103
03104 void EnvSIPPLat::ClearStates(){
03105 SBPL_PRINTF("clearing states...\n");
03106 for(unsigned int i=0; i<StateID2CoordTable.size(); i++)
03107 StateID2CoordTable[i]->T = -1;
03108
03109
03110
03111
03112
03113
03114
03115
03116
03117
03118
03119
03120 SBPL_PRINTF("done clearing states\n");
03121 }
03122
03123 envSIPPLatHashEntry_t* EnvSIPPLat::getEntryFromID(int id){
03124 return StateID2CoordTable[id];
03125 }
03126
03127 void EnvSIPPLat::PrintState(int stateID, bool bVerbose, FILE* fOut )
03128 {
03129 #if DEBUG
03130 if(stateID >= (int)StateID2CoordTable.size())
03131 {
03132 SBPL_ERROR("ERROR in envSIPPLat... function: stateID illegal (2)\n");
03133 throw new SBPL_Exception();
03134 }
03135 #endif
03136
03137 if(fOut == NULL)
03138 fOut = stdout;
03139
03140 envSIPPLatHashEntry_t* HashEntry = StateID2CoordTable[stateID];
03141 envSIPPLatHashEntry_t* GoalHashEntry = StateID2CoordTable[envSIPPLat.goalstateid];
03142
03143 if(HashEntry->X == GoalHashEntry->X && HashEntry->Y == GoalHashEntry->Y && HashEntry->Theta == GoalHashEntry->Theta && bVerbose)
03144 {
03145 SBPL_FPRINTF(fOut, "the state is a goal state\n");
03146 }
03147
03148 if(bVerbose)
03149 SBPL_FPRINTF(fOut, "X=%d Y=%d Theta=%d T=%d\n", HashEntry->X, HashEntry->Y, HashEntry->Theta, HashEntry->T);
03150 else
03151 SBPL_FPRINTF(fOut, "%.3f %.3f %.3f %.3f\n", DISCXY2CONT(HashEntry->X, envSIPPLatCfg.cellsize_m), DISCXY2CONT(HashEntry->Y,envSIPPLatCfg.cellsize_m),
03152 DiscTheta2Cont(HashEntry->Theta, ENVSIPPLAT_THETADIRS), DISCTIME2CONT(HashEntry->T, envSIPPLatCfg.timeResolution));
03153
03154 }
03155
03156
03157 envSIPPLatHashEntry_t* EnvSIPPLat::GetHashEntry(int X, int Y, int Theta, int interval, int T)
03158 {
03159
03160 #if TIME_DEBUG
03161 clock_t currenttime = clock();
03162 #endif
03163
03164 if(interval < 0){
03165 SBPL_ERROR("ERROR: tried to get a Hash Entry (x=%d y=%d theta=%d interval=%d) in a collision interval!\n", X,Y,Theta,interval);
03166 throw new SBPL_Exception();
03167 }
03168
03169 int binid = GETHASHBIN(X, Y, Theta, interval);
03170
03171 #if DEBUG
03172 if ((int)Coord2StateIDHashTable[binid].size() > 500)
03173 {
03174 SBPL_PRINTF("WARNING: Hash table has a bin %d (X=%d Y=%d) of size %d\n",
03175 binid, X, Y, Coord2StateIDHashTable[binid].size());
03176
03177 PrintHashTableHist();
03178 }
03179 #endif
03180
03181
03182 for(int ind = 0; ind < (int)Coord2StateIDHashTable[binid].size(); ind++)
03183 {
03184 if( Coord2StateIDHashTable[binid][ind]->X == X
03185 && Coord2StateIDHashTable[binid][ind]->Y == Y
03186 && Coord2StateIDHashTable[binid][ind]->Theta == Theta
03187 && Coord2StateIDHashTable[binid][ind]->Interval == interval)
03188 {
03189 #if TIME_DEBUG
03190 time_gethash += clock()-currenttime;
03191 #endif
03192 if(Coord2StateIDHashTable[binid][ind]->T < 0)
03193 Coord2StateIDHashTable[binid][ind]->T = T;
03194 return Coord2StateIDHashTable[binid][ind];
03195 }
03196 }
03197
03198 #if TIME_DEBUG
03199 time_gethash += clock()-currenttime;
03200 #endif
03201
03202 return NULL;
03203 }
03204
03205
03206 envSIPPLatHashEntry_t* EnvSIPPLat::CreateNewHashEntry(int X, int Y, int Theta, int interval, int T)
03207 {
03208 int i;
03209
03210 #if TIME_DEBUG
03211 clock_t currenttime = clock();
03212 #endif
03213
03214 if(interval < 0){
03215 SBPL_ERROR("ERROR: tried to create a Hash Entry (x=%d y=%d theta=%d interval=%d t=%d) in a collision interval!\n", X,Y,Theta,interval,T);
03216 throw new SBPL_Exception();
03217 }
03218
03219 envSIPPLatHashEntry_t* HashEntry = new envSIPPLatHashEntry_t;
03220
03221 HashEntry->X = X;
03222 HashEntry->Y = Y;
03223 HashEntry->Theta = Theta;
03224 HashEntry->T = T;
03225 HashEntry->Interval = interval;
03226 HashEntry->iteration = 0;
03227 HashEntry->closed = false;
03228
03229 HashEntry->stateID = StateID2CoordTable.size();
03230
03231
03232 StateID2CoordTable.push_back(HashEntry);
03233
03234
03235
03236 i = GETHASHBIN(HashEntry->X, HashEntry->Y, HashEntry->Theta, HashEntry->Interval);
03237
03238
03239
03240 Coord2StateIDHashTable[i].push_back(HashEntry);
03241
03242
03243 int* entry = new int [NUMOFINDICES_STATEID2IND];
03244 StateID2IndexMapping.push_back(entry);
03245 for(i = 0; i < NUMOFINDICES_STATEID2IND; i++)
03246 {
03247 StateID2IndexMapping[HashEntry->stateID][i] = -1;
03248 }
03249
03250 if(HashEntry->stateID != (int)StateID2IndexMapping.size()-1)
03251 {
03252 SBPL_ERROR("ERROR in Env... function: last state has incorrect stateID\n");
03253 throw new SBPL_Exception();
03254 }
03255
03256 #if TIME_DEBUG
03257 time_createhash += clock()-currenttime;
03258 #endif
03259
03260 return HashEntry;
03261 }
03262
03263 void EnvSIPPLat::GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV, vector<envSIPPLatAction_t*>* actionV )
03264 {
03265 int aind;
03266
03267
03268 #if TIME_DEBUG
03269 clock_t currenttime = clock();
03270 #endif
03271
03272
03273 SuccIDV->clear();
03274 CostV->clear();
03275 SuccIDV->reserve(envSIPPLatCfg.actionwidth);
03276 CostV->reserve(envSIPPLatCfg.actionwidth);
03277 if(actionV != NULL)
03278 {
03279 actionV->clear();
03280 actionV->reserve(envSIPPLatCfg.actionwidth);
03281 }
03282
03283
03284 envSIPPLatHashEntry_t* HashEntry = StateID2CoordTable[SourceStateID];
03285 HashEntry->closed = true;
03286 envSIPPLatHashEntry_t* GoalHashEntry = StateID2CoordTable[envSIPPLat.goalstateid];
03287
03288
03289
03290
03291
03292
03293
03294
03295
03296
03297
03298
03299
03300 if(SourceStateID == envSIPPLat.goalstateid){
03301 return;
03302 }
03303
03304
03305 for (aind = 0; aind < envSIPPLatCfg.actionwidth; aind++){
03306
03307
03308 envSIPPLatAction_t* nav4daction = &envSIPPLatCfg.ActionsV[(int)HashEntry->Theta][aind];
03309 int newX = HashEntry->X + nav4daction->dX;
03310 int newY = HashEntry->Y + nav4daction->dY;
03311 int newTheta = NORMALIZEDISCTHETA(nav4daction->endtheta, ENVSIPPLAT_THETADIRS);
03312
03313
03314
03315
03316
03317 if(!IsValidCell(newX, newY))
03318 continue;
03319
03320
03321
03322
03323
03324 int base_cost = GetActionCost(HashEntry->X, HashEntry->Y, HashEntry->Theta, nav4daction);
03325 if(base_cost >= INFINITECOST)
03326 continue;
03327
03328
03329
03330
03331
03332 vector<int> intervals;
03333 vector<int> times;
03334 getIntervals(&intervals, ×, HashEntry, nav4daction);
03335
03336
03337
03338 for(unsigned int i=0; i<intervals.size(); i++){
03339 envSIPPLatHashEntry_t* OutHashEntry;
03340
03341 if(newX == GoalHashEntry->X && newY == GoalHashEntry->Y && newTheta == GoalHashEntry->Theta){
03342 OutHashEntry = GoalHashEntry;
03343 if(times[i] < OutHashEntry->T)
03344 OutHashEntry->T = times[i];
03345 if(intervals[i] < OutHashEntry->Interval)
03346 OutHashEntry->Interval = intervals[i];
03347 SBPL_PRINTF("found goal at t=%d\n",OutHashEntry->T);
03348 }
03349 else if((OutHashEntry = GetHashEntry(newX, newY, newTheta, intervals[i], times[i])) == NULL){
03350
03351 OutHashEntry = CreateNewHashEntry(newX, newY, newTheta, intervals[i], times[i]);
03352 }
03353
03354
03355
03356
03357
03358 else if(times[i] < OutHashEntry->T){
03359
03360
03361 OutHashEntry->T = times[i];
03362 }
03363
03364 int cost = base_cost + (int)(ENVSIPPLAT_COSTMULT_MTOMM*(times[i]-HashEntry->T-nav4daction->dT)*envSIPPLatCfg.timeResolution);
03365
03366 SuccIDV->push_back(OutHashEntry->stateID);
03367
03368
03369
03370
03371
03372
03373
03374
03375
03376
03377
03378
03379
03380
03381
03382
03383
03384 CostV->push_back(cost);
03385
03386
03387 if(actionV != NULL)
03388 actionV->push_back(nav4daction);
03389 }
03390 }
03391
03392 #if TIME_DEBUG
03393 time_getsuccs += clock()-currenttime;
03394 #endif
03395
03396
03397
03398 }
03399
03400
03401
03402 void EnvSIPPLat::GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* CostV)
03403 {
03404
03405 SBPL_PRINTF("Error: This environment currently does not support backward planning!\n");
03406 throw new SBPL_Exception();
03407
03408
03409
03410
03411 int aind;
03412
03413 #if TIME_DEBUG
03414 clock_t currenttime = clock();
03415 #endif
03416
03417
03418 PredIDV->clear();
03419 CostV->clear();
03420 PredIDV->reserve(envSIPPLatCfg.actionwidth);
03421 CostV->reserve(envSIPPLatCfg.actionwidth);
03422
03423
03424 envSIPPLatHashEntry_t* HashEntry = StateID2CoordTable[TargetStateID];
03425
03426
03427 bool bTestBounds = false;
03428 if(HashEntry->X == 0 || HashEntry->X == envSIPPLatCfg.EnvWidth_c-1 ||
03429 HashEntry->Y == 0 || HashEntry->Y == envSIPPLatCfg.EnvHeight_c-1)
03430 bTestBounds = true;
03431
03432 for (aind = 0; aind < (int)envSIPPLatCfg.PredActionsV[(int)HashEntry->Theta].size(); aind++)
03433 {
03434
03435 envSIPPLatAction_t* nav4daction = envSIPPLatCfg.PredActionsV[(int)HashEntry->Theta].at(aind);
03436
03437 int predX = HashEntry->X - nav4daction->dX;
03438 int predY = HashEntry->Y - nav4daction->dY;
03439 int predTheta = nav4daction->starttheta;
03440 int predT = HashEntry->T - nav4daction->dT;
03441
03442
03443
03444 if(bTestBounds){
03445 if(!IsValidCell(predX, predY))
03446 continue;
03447 }
03448
03449
03450 int cost = GetActionCost(predX, predY, predTheta, nav4daction);
03451 if(cost >= INFINITECOST)
03452 continue;
03453
03454 envSIPPLatHashEntry_t* OutHashEntry;
03455 if((OutHashEntry = GetHashEntry(predX, predY, predTheta, getInterval(predX, predY, predT), predT)) == NULL)
03456 {
03457
03458 OutHashEntry = CreateNewHashEntry(predX, predY, predTheta, getInterval(predX, predY, predT), predT);
03459 }
03460
03461 PredIDV->push_back(OutHashEntry->stateID);
03462 CostV->push_back(cost);
03463 }
03464
03465 #if TIME_DEBUG
03466 time_getsuccs += clock()-currenttime;
03467 #endif
03468
03469
03470 }
03471
03472 void EnvSIPPLat::SetAllActionsandAllOutcomes(CMDPSTATE* state)
03473 {
03474
03475 int cost;
03476
03477 #if DEBUG
03478 if(state->StateID >= (int)StateID2CoordTable.size())
03479 {
03480 SBPL_ERROR("ERROR in Env... function: stateID illegal\n");
03481 throw new SBPL_Exception();
03482 }
03483
03484 if((int)state->Actions.size() != 0)
03485 {
03486 SBPL_ERROR("ERROR in Env_setAllActionsandAllOutcomes: actions already exist for the state\n");
03487 throw new SBPL_Exception();
03488 }
03489 #endif
03490
03491
03492
03493 envSIPPLatHashEntry_t* HashEntry = StateID2CoordTable[state->StateID];
03494 envSIPPLatHashEntry_t* GoalHashEntry = StateID2CoordTable[envSIPPLat.goalstateid];
03495
03496
03497 if(HashEntry->X == GoalHashEntry->X && HashEntry->Y == GoalHashEntry->Y && HashEntry->Theta == GoalHashEntry->Theta)
03498 return;
03499
03500
03501 bool bTestBounds = false;
03502 if(HashEntry->X == 0 || HashEntry->X == envSIPPLatCfg.EnvWidth_c-1 ||
03503 HashEntry->Y == 0 || HashEntry->Y == envSIPPLatCfg.EnvHeight_c-1)
03504 bTestBounds = true;
03505 for (int aind = 0; aind < envSIPPLatCfg.actionwidth; aind++)
03506 {
03507 envSIPPLatAction_t* nav4daction = &envSIPPLatCfg.ActionsV[(int)HashEntry->Theta][aind];
03508 int newX = HashEntry->X + nav4daction->dX;
03509 int newY = HashEntry->Y + nav4daction->dY;
03510 int newTheta = NORMALIZEDISCTHETA(nav4daction->endtheta, ENVSIPPLAT_THETADIRS);
03511 int newT = HashEntry->T + nav4daction->dT;
03512
03513
03514 if(bTestBounds){
03515 if(!IsValidCell(newX, newY))
03516 continue;
03517 }
03518
03519
03520 cost = GetActionCost(HashEntry->X, HashEntry->Y, HashEntry->Theta, nav4daction);
03521 if(cost >= INFINITECOST)
03522 continue;
03523
03524
03525 CMDPACTION* action = state->AddAction(aind);
03526
03527 #if TIME_DEBUG
03528 clock_t currenttime = clock();
03529 #endif
03530
03531 envSIPPLatHashEntry_t* OutHashEntry;
03532 if((OutHashEntry = GetHashEntry(newX, newY, newTheta, getInterval(newX, newY, newT), newT)) == NULL)
03533 {
03534
03535 OutHashEntry = CreateNewHashEntry(newX, newY, newTheta, getInterval(newX, newY, newT), newT);
03536 }
03537 action->AddOutcome(OutHashEntry->stateID, cost, 1.0);
03538
03539 #if TIME_DEBUG
03540 time3_addallout += clock()-currenttime;
03541 #endif
03542
03543 }
03544 }
03545
03546
03547 void EnvSIPPLat::GetPredsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *preds_of_changededgesIDV)
03548 {
03549 nav2dcell_t cell;
03550 SBPL_4Dcell_t affectedcell;
03551 envSIPPLatHashEntry_t* affectedHashEntry;
03552
03553
03554 iteration++;
03555
03556 for(int i = 0; i < (int)changedcellsV->size(); i++)
03557 {
03558 cell = changedcellsV->at(i);
03559
03560
03561 for(int sind = 0; sind < (int)affectedpredstatesV.size(); sind++)
03562 {
03563 affectedcell = affectedpredstatesV.at(sind);
03564
03565
03566 affectedcell.x = affectedcell.x + cell.x;
03567 affectedcell.y = affectedcell.y + cell.y;
03568
03569
03570 affectedHashEntry = GetHashEntry(affectedcell.x, affectedcell.y, affectedcell.theta, getInterval(affectedcell.x, affectedcell.y, affectedcell.t), affectedcell.t);
03571 if(affectedHashEntry != NULL && affectedHashEntry->iteration < iteration)
03572 {
03573 preds_of_changededgesIDV->push_back(affectedHashEntry->stateID);
03574 affectedHashEntry->iteration = iteration;
03575 }
03576 }
03577 }
03578 }
03579
03580 void EnvSIPPLat::GetSuccsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *succs_of_changededgesIDV)
03581 {
03582 nav2dcell_t cell;
03583 SBPL_4Dcell_t affectedcell;
03584 envSIPPLatHashEntry_t* affectedHashEntry;
03585
03586 SBPL_ERROR("ERROR: getsuccs is not supported currently\n");
03587 throw new SBPL_Exception();
03588
03589
03590 iteration++;
03591
03592
03593 for(int i = 0; i < (int)changedcellsV->size(); i++)
03594 {
03595 cell = changedcellsV->at(i);
03596
03597
03598 for(int sind = 0; sind < (int)affectedsuccstatesV.size(); sind++)
03599 {
03600 affectedcell = affectedsuccstatesV.at(sind);
03601
03602
03603 affectedcell.x = affectedcell.x + cell.x;
03604 affectedcell.y = affectedcell.y + cell.y;
03605
03606
03607 affectedHashEntry = GetHashEntry(affectedcell.x, affectedcell.y, affectedcell.theta, getInterval(affectedcell.x, affectedcell.y, affectedcell.t), affectedcell.t);
03608 if(affectedHashEntry != NULL && affectedHashEntry->iteration < iteration)
03609 {
03610 succs_of_changededgesIDV->push_back(affectedHashEntry->stateID);
03611 affectedHashEntry->iteration = iteration;
03612 }
03613 }
03614 }
03615 }
03616
03617 void EnvSIPPLat::InitializeEnvironment()
03618 {
03619 envSIPPLatHashEntry_t* HashEntry;
03620
03621
03622 HashTableSize = 64*1024;
03623 Coord2StateIDHashTable = new vector<envSIPPLatHashEntry_t*>[HashTableSize];
03624
03625
03626 StateID2CoordTable.clear();
03627
03628
03629 if(getInterval(envSIPPLatCfg.StartX_c, envSIPPLatCfg.StartY_c, envSIPPLatCfg.StartTime) < 0){
03630 SBPL_PRINTF("WARNING: start time (%d %d %d) is invalid\n", envSIPPLatCfg.StartX_c, envSIPPLatCfg.StartY_c, envSIPPLatCfg.StartTime);
03631 }
03632 HashEntry = CreateNewHashEntry(envSIPPLatCfg.StartX_c, envSIPPLatCfg.StartY_c, envSIPPLatCfg.StartTheta, getInterval(envSIPPLatCfg.StartX_c, envSIPPLatCfg.StartY_c, envSIPPLatCfg.StartTime), envSIPPLatCfg.StartTime);
03633 envSIPPLat.startstateid = HashEntry->stateID;
03634 SBPL_PRINTF("id=%d X=%d Y=%d Theta=%d T=%d\n", HashEntry->stateID, HashEntry->X, HashEntry->Y, HashEntry->Theta, HashEntry->T);
03635
03636
03637 HashEntry = CreateNewHashEntry(envSIPPLatCfg.EndX_c, envSIPPLatCfg.EndY_c, envSIPPLatCfg.EndTheta, INFINITECOST, INFINITECOST);
03638 envSIPPLat.goalstateid = HashEntry->stateID;
03639
03640
03641 envSIPPLat.bInitialized = true;
03642
03643 }
03644
03645
03646
03647
03648
03649 unsigned int EnvSIPPLat::GETHASHBIN(unsigned int X1, unsigned int X2, unsigned int Theta, unsigned int interval)
03650 {
03651
03652 return inthash(inthash(X1)+(inthash(X2)<<1)+(inthash(Theta)<<2)+(inthash(interval)<<3)) & (HashTableSize-1);
03653 }
03654
03655 void EnvSIPPLat::PrintHashTableHist()
03656 {
03657 int s0=0, s1=0, s50=0, s100=0, s200=0, s300=0, slarge=0;
03658
03659 for(int j = 0; j < HashTableSize; j++)
03660 {
03661 if((int)Coord2StateIDHashTable[j].size() == 0)
03662 s0++;
03663 else if((int)Coord2StateIDHashTable[j].size() < 50)
03664 s1++;
03665 else if((int)Coord2StateIDHashTable[j].size() < 100)
03666 s50++;
03667 else if((int)Coord2StateIDHashTable[j].size() < 200)
03668 s100++;
03669 else if((int)Coord2StateIDHashTable[j].size() < 300)
03670 s200++;
03671 else if((int)Coord2StateIDHashTable[j].size() < 400)
03672 s300++;
03673 else
03674 slarge++;
03675 }
03676 SBPL_PRINTF("hash table histogram: 0:%d, <50:%d, <100:%d, <200:%d, <300:%d, <400:%d >400:%d\n",
03677 s0,s1, s50, s100, s200,s300,slarge);
03678 }
03679
03680 void EnvSIPPLat::getExpansions(vector<SBPL_4Dpt_t>* points){
03681 for(unsigned int i=0; i<StateID2CoordTable.size(); i++){
03682 envSIPPLatHashEntry_t* state = StateID2CoordTable[i];
03683 if(state->closed){
03684 SBPL_4Dpt_t p;
03685 p.x = DISCXY2CONT(state->X, envSIPPLatCfg.cellsize_m);
03686 p.y = DISCXY2CONT(state->Y, envSIPPLatCfg.cellsize_m);
03687 p.theta = DISCXY2CONT(state->Theta, ENVSIPPLAT_THETADIRS);
03688 p.t = DISCTIME2CONT(state->T, envSIPPLatCfg.timeResolution);
03689 points->push_back(p);
03690 }
03691 }
03692 }
03693
03694 void EnvSIPPLat::dumpStatesToFile(){
03695 FILE* fout = fopen("state_dump_interval.txt", "w");
03696 for(unsigned int i=0; i<StateID2CoordTable.size(); i++){
03697 envSIPPLatHashEntry_t* state = StateID2CoordTable[i];
03698
03699 SBPL_FPRINTF(fout, "%d %d %d %d %d\n", state->X, state->Y, state->Theta, state->Interval, state->T);
03700 }
03701 fclose(fout);
03702 }
03703
03704 void EnvSIPPLat::dumpEnvironmentToFile(){
03705 FILE* fout = fopen("hall.cfg", "w");
03706 SBPL_FPRINTF(fout, "discretization(cells): %d %d\n", envSIPPLatCfg.EnvWidth_c, envSIPPLatCfg.EnvHeight_c);
03707 SBPL_FPRINTF(fout, "obsthresh: %d\n", envSIPPLatCfg.obsthresh);
03708 SBPL_FPRINTF(fout, "cost_inscribed_thresh: %d\n", envSIPPLatCfg.cost_inscribed_thresh);
03709 SBPL_FPRINTF(fout, "cost_possibly_circumscribed_thresh: %d\n", envSIPPLatCfg.cost_possibly_circumscribed_thresh);
03710 SBPL_FPRINTF(fout, "dynamic_obstacle_collision_cost_thresh: %d\n", envSIPPLatCfg.dynamic_obstacle_collision_cost_thresh);
03711 SBPL_FPRINTF(fout, "cellsize(meters): %f\n", envSIPPLatCfg.cellsize_m);
03712 SBPL_FPRINTF(fout, "timeResolution(seconds): %f\n", envSIPPLatCfg.timeResolution);
03713 SBPL_FPRINTF(fout, "nominalvel(mpersecs): %f\n", envSIPPLatCfg.nominalvel_mpersecs);
03714 SBPL_FPRINTF(fout, "timetoturn45degsinplace(secs): %f\n", envSIPPLatCfg.timetoturn45degsinplace_secs);
03715 SBPL_FPRINTF(fout, "start(meters,rads): %f %f %f %f\n", DISCXY2CONT(envSIPPLatCfg.StartX_c, envSIPPLatCfg.cellsize_m), DISCXY2CONT(envSIPPLatCfg.StartY_c, envSIPPLatCfg.cellsize_m), DiscTheta2Cont(envSIPPLatCfg.StartTheta, ENVSIPPLAT_THETADIRS), DISCTIME2CONT(envSIPPLatCfg.StartTime, envSIPPLatCfg.timeResolution));
03716 SBPL_FPRINTF(fout, "end(meters,rads): %f %f %f\n", DISCXY2CONT(envSIPPLatCfg.EndX_c, envSIPPLatCfg.cellsize_m), DISCXY2CONT(envSIPPLatCfg.EndY_c, envSIPPLatCfg.cellsize_m), DiscTheta2Cont(envSIPPLatCfg.EndTheta, ENVSIPPLAT_THETADIRS));
03717 SBPL_FPRINTF(fout, "environment:\n");
03718
03719 for(int y=0; y<envSIPPLatCfg.EnvHeight_c; y++){
03720 for(int x=0; x<envSIPPLatCfg.EnvWidth_c; x++){
03721 SBPL_FPRINTF(fout, "%d ", envSIPPLatCfg.Grid2D[x][y]);
03722 }
03723 SBPL_FPRINTF(fout, "\n");
03724 }
03725 fclose(fout);
03726 }
03727
03728 void EnvSIPPLat::dumpDynamicObstaclesToFile(){
03729 FILE* fout = fopen("hall_dynobs.dob", "w");
03730 SBPL_FPRINTF(fout, "NumberOfDynamicObstacles: %d\n", (int)dynamicObstacles.size());
03731 for(unsigned int i=0; i<dynamicObstacles.size(); i++){
03732 SBPL_FPRINTF(fout, "DynamicObstacleID: %d\n", i);
03733 SBPL_FPRINTF(fout, "ObstacleRadius: %f\n", dynamicObstacles[i].radius - envSIPPLatCfg.robotRadius);
03734 SBPL_FPRINTF(fout, "NumberOfTrajectories: %d\n", (int)dynamicObstacles[i].trajectories.size());
03735 for(unsigned int j=0; j<dynamicObstacles[i].trajectories.size(); j++){
03736 SBPL_FPRINTF(fout, "TrajectoryID: %d\n", j);
03737 SBPL_FPRINTF(fout, "TrajectoryProbability: %f\n", dynamicObstacles[i].trajectories[j].prob);
03738 SBPL_FPRINTF(fout, "NumberOfPoints: %d\n", (int)dynamicObstacles[i].trajectories[j].points.size());
03739 for(unsigned int k=0; k<dynamicObstacles[i].trajectories[j].points.size(); k++){
03740 SBPL_FPRINTF(fout, "%f %f %f %f\n", dynamicObstacles[i].trajectories[j].points[k].x, dynamicObstacles[i].trajectories[j].points[k].y, DISCTIME2CONT(dynamicObstacles[i].trajectories[j].points[k].t, envSIPPLatCfg.timeResolution), dynamicObstacles[i].trajectories[j].points[k].std_dev);
03741 }
03742 SBPL_FPRINTF(fout, "ObstacleExistsAfterTrajectory: %d\n", dynamicObstacles[i].trajectories[j].existsAfter);
03743 }
03744 }
03745 fclose(fout);
03746 }
03747
03748 int EnvSIPPLat::GetFromToHeuristic(int FromStateID, int ToStateID)
03749 {
03750
03751 #if USE_HEUR==0
03752 return 0;
03753 #endif
03754
03755
03756 #if DEBUG
03757 if(FromStateID >= (int)StateID2CoordTable.size()
03758 || ToStateID >= (int)StateID2CoordTable.size())
03759 {
03760 SBPL_ERROR("ERROR in envSIPPLat... function: stateID illegal\n");
03761 throw new SBPL_Exception();
03762 }
03763 #endif
03764
03765
03766 envSIPPLatHashEntry_t* FromHashEntry = StateID2CoordTable[FromStateID];
03767 envSIPPLatHashEntry_t* ToHashEntry = StateID2CoordTable[ToStateID];
03768
03769
03770
03771
03772 return (int)(ENVSIPPLAT_COSTMULT_MTOMM*EuclideanDistance_m(FromHashEntry->X, FromHashEntry->Y, ToHashEntry->X, ToHashEntry->Y)/envSIPPLatCfg.nominalvel_mpersecs);
03773
03774 }
03775
03776
03777 int EnvSIPPLat::GetGoalHeuristic(int stateID)
03778 {
03779 #if USE_HEUR==0
03780 return 0;
03781 #endif
03782
03783 #if DEBUG
03784 if(stateID >= (int)StateID2CoordTable.size())
03785 {
03786 SBPL_ERROR("ERROR in envSIPPLat... function: stateID illegal\n");
03787 throw new SBPL_Exception();
03788 }
03789 #endif
03790
03791 if(bNeedtoRecomputeGoalHeuristics)
03792 {
03793 grid2Dsearchfromgoal->search(envSIPPLatCfg.Grid2D, envSIPPLatCfg.cost_inscribed_thresh,
03794 envSIPPLatCfg.EndX_c, envSIPPLatCfg.EndY_c, envSIPPLatCfg.StartX_c, envSIPPLatCfg.StartY_c,
03795 SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS);
03796 bNeedtoRecomputeGoalHeuristics = false;
03797 SBPL_PRINTF("2dsolcost_infullunits=%d\n", (int)(grid2Dsearchfromgoal->getlowerboundoncostfromstart_inmm(envSIPPLatCfg.StartX_c, envSIPPLatCfg.StartY_c)
03798 /envSIPPLatCfg.nominalvel_mpersecs));
03799
03800 #if DEBUG
03801 PrintHeuristicValues();
03802 #endif
03803
03804 }
03805
03806 envSIPPLatHashEntry_t* HashEntry = StateID2CoordTable[stateID];
03807 int h2D = grid2Dsearchfromgoal->getlowerboundoncostfromstart_inmm(HashEntry->X, HashEntry->Y);
03808 int hEuclid = (int)(ENVSIPPLAT_COSTMULT_MTOMM*EuclideanDistance_m(HashEntry->X, HashEntry->Y, envSIPPLatCfg.EndX_c, envSIPPLatCfg.EndY_c));
03809
03810
03811 #if DEBUG
03812 SBPL_FPRINTF(fDeb, "h2D = %d hEuclid = %d\n", h2D, hEuclid);
03813 #endif
03814
03815
03816 return (int)(((double)__max(h2D,hEuclid))/envSIPPLatCfg.nominalvel_mpersecs);
03817
03818 }
03819
03820
03821 int EnvSIPPLat::GetStartHeuristic(int stateID)
03822 {
03823
03824
03825 #if USE_HEUR==0
03826 return 0;
03827 #endif
03828
03829
03830 #if DEBUG
03831 if(stateID >= (int)StateID2CoordTable.size())
03832 {
03833 SBPL_ERROR("ERROR in envSIPPLat... function: stateID illegal\n");
03834 throw new SBPL_Exception();
03835 }
03836 #endif
03837
03838
03839 if(bNeedtoRecomputeStartHeuristics)
03840 {
03841 grid2Dsearchfromstart->search(envSIPPLatCfg.Grid2D, envSIPPLatCfg.cost_inscribed_thresh,
03842 envSIPPLatCfg.StartX_c, envSIPPLatCfg.StartY_c, envSIPPLatCfg.EndX_c, envSIPPLatCfg.EndY_c,
03843 SBPL_2DGRIDSEARCH_TERM_CONDITION_ALLCELLS);
03844 bNeedtoRecomputeStartHeuristics = false;
03845 SBPL_PRINTF("2dsolcost_infullunits=%d\n", (int)(grid2Dsearchfromstart->getlowerboundoncostfromstart_inmm(envSIPPLatCfg.EndX_c, envSIPPLatCfg.EndY_c)
03846 /envSIPPLatCfg.nominalvel_mpersecs));
03847
03848 #if DEBUG
03849 PrintHeuristicValues();
03850 #endif
03851
03852 }
03853
03854 envSIPPLatHashEntry_t* HashEntry = StateID2CoordTable[stateID];
03855 int h2D = grid2Dsearchfromstart->getlowerboundoncostfromstart_inmm(HashEntry->X, HashEntry->Y);
03856 int hEuclid = (int)(ENVSIPPLAT_COSTMULT_MTOMM*EuclideanDistance_m(envSIPPLatCfg.StartX_c, envSIPPLatCfg.StartY_c, HashEntry->X, HashEntry->Y));
03857
03858
03859 #if DEBUG
03860 SBPL_FPRINTF(fDeb, "h2D = %d hEuclid = %d\n", h2D, hEuclid);
03861 #endif
03862
03863
03864 return (int)(((double)__max(h2D,hEuclid))/envSIPPLatCfg.nominalvel_mpersecs);
03865
03866 }
03867
03868 int EnvSIPPLat::SizeofCreatedEnv()
03869 {
03870 return (int)StateID2CoordTable.size();
03871
03872 }
03873