$search
00001 /* 00002 * Copyright (c) 2008, Maxim Likhachev 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the University of Pennsylvania nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 #include <iostream> 00030 using namespace std; 00031 00032 #include "../../sbpl/headers.h" 00033 00034 00035 #if TIME_DEBUG 00036 static clock_t time3_addallout = 0; 00037 static clock_t time_gethash = 0; 00038 static clock_t time_createhash = 0; 00039 static clock_t time_getsuccs = 0; 00040 #endif 00041 00042 static long int checks = 0; 00043 00044 00045 //-----------------constructors/destructors------------------------------- 00046 EnvironmentNAVXYTHETAMLEVLAT::EnvironmentNAVXYTHETAMLEVLAT() 00047 { 00048 numofadditionalzlevs = 0; //by default there is only base level, no additional levels 00049 AddLevelFootprintPolygonV = NULL; 00050 AdditionalInfoinActionsV = NULL; 00051 AddLevelGrid2D = NULL; 00052 AddLevel_cost_possibly_circumscribed_thresh = NULL; 00053 AddLevel_cost_inscribed_thresh = NULL; 00054 } 00055 00056 EnvironmentNAVXYTHETAMLEVLAT::~EnvironmentNAVXYTHETAMLEVLAT() 00057 { 00058 if(AddLevelFootprintPolygonV != NULL) 00059 { 00060 delete [] AddLevelFootprintPolygonV; 00061 AddLevelFootprintPolygonV = NULL; 00062 } 00063 00064 if(AdditionalInfoinActionsV != NULL) 00065 { 00066 for(int tind = 0; tind < NAVXYTHETALAT_THETADIRS; tind++) 00067 { 00068 for (int aind = 0; aind < EnvNAVXYTHETALATCfg.actionwidth; aind++) 00069 { 00070 delete [] AdditionalInfoinActionsV[tind][aind].intersectingcellsV; 00071 } 00072 delete [] AdditionalInfoinActionsV[tind]; 00073 } 00074 delete [] AdditionalInfoinActionsV; 00075 AdditionalInfoinActionsV = NULL; 00076 } 00077 00078 if(AddLevelGrid2D != NULL) 00079 { 00080 for(int levelind = 0; levelind < numofadditionalzlevs; levelind++) 00081 { 00082 for (int xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { 00083 delete [] AddLevelGrid2D[levelind][xind]; 00084 } 00085 delete [] AddLevelGrid2D[levelind]; 00086 } 00087 delete [] AddLevelGrid2D; 00088 AddLevelGrid2D = NULL; 00089 } 00090 00091 if(AddLevel_cost_possibly_circumscribed_thresh != NULL) 00092 { 00093 delete [] AddLevel_cost_possibly_circumscribed_thresh; 00094 AddLevel_cost_possibly_circumscribed_thresh = NULL; 00095 } 00096 00097 if(AddLevel_cost_inscribed_thresh != NULL) 00098 { 00099 delete [] AddLevel_cost_inscribed_thresh; 00100 AddLevel_cost_inscribed_thresh = NULL; 00101 } 00102 00103 //reset the number of additional levels 00104 numofadditionalzlevs = 0; 00105 } 00106 00107 00108 //--------------------------------------------------------------------- 00109 00110 00111 00112 //-------------------problem specific and local functions--------------------- 00113 00114 //returns true if cell is traversable and within map limits - it checks against all levels including the base one 00115 bool EnvironmentNAVXYTHETAMLEVLAT::IsValidCell(int X, int Y) 00116 { 00117 int levelind; 00118 00119 if(!EnvironmentNAVXYTHETALAT::IsValidCell(X,Y)) 00120 return false; 00121 00122 //iterate through the additional levels 00123 for (levelind=0; levelind < numofadditionalzlevs; levelind++) 00124 { 00125 if(AddLevelGrid2D[levelind][X][Y] >= EnvNAVXYTHETALATCfg.obsthresh) 00126 return false; 00127 } 00128 //otherwise the cell is valid at all levels 00129 return true; 00130 } 00131 00132 // returns true if cell is traversable and within map limits for a particular level 00133 bool EnvironmentNAVXYTHETAMLEVLAT::IsValidCell(int X, int Y, int levind) 00134 { 00135 return (X >= 0 && X < EnvNAVXYTHETALATCfg.EnvWidth_c && 00136 Y >= 0 && Y < EnvNAVXYTHETALATCfg.EnvHeight_c && levind < numofadditionalzlevs && 00137 AddLevelGrid2D[levind][X][Y] < EnvNAVXYTHETALATCfg.obsthresh); 00138 } 00139 00140 00141 //returns true if cell is untraversable at all levels 00142 bool EnvironmentNAVXYTHETAMLEVLAT::IsObstacle(int X, int Y) 00143 { 00144 00145 int levelind; 00146 00147 if(EnvironmentNAVXYTHETALAT::IsObstacle(X,Y)) 00148 return true; 00149 00150 //iterate through the additional levels 00151 for (levelind=0; levelind < numofadditionalzlevs; levelind++) 00152 { 00153 if(AddLevelGrid2D[levelind][X][Y] >= EnvNAVXYTHETALATCfg.obsthresh) 00154 return true; 00155 } 00156 //otherwise the cell is obstacle-free at all cells 00157 return false; 00158 00159 00160 } 00161 00162 //returns true if cell is untraversable in level # levelnum. If levelnum = -1, then it checks all levels 00163 bool EnvironmentNAVXYTHETAMLEVLAT::IsObstacle(int X, int Y, int levind) 00164 { 00165 #if DEBUG 00166 if(levind >= numofadditionalzlevs) 00167 { 00168 SBPL_ERROR("ERROR: IsObstacle invoked at level %d\n", levind); 00169 SBPL_FPRINTF(fDeb, "ERROR: IsObstacle invoked at level %d\n", levind); 00170 return false; 00171 } 00172 #endif 00173 00174 return (AddLevelGrid2D[levind][X][Y] >= EnvNAVXYTHETALATCfg.obsthresh); 00175 } 00176 00177 // returns the maximum over all levels of the cost corresponding to the cell <x,y> 00178 unsigned char EnvironmentNAVXYTHETAMLEVLAT::GetMapCost(int X, int Y) 00179 { 00180 unsigned char mapcost = EnvNAVXYTHETALATCfg.Grid2D[X][Y]; 00181 00182 for (int levind=0; levind < numofadditionalzlevs; levind++) 00183 { 00184 mapcost = __max(mapcost, AddLevelGrid2D[levind][X][Y]); 00185 } 00186 00187 return mapcost; 00188 } 00189 00190 // returns the cost corresponding to the cell <x,y> at level levind 00191 unsigned char EnvironmentNAVXYTHETAMLEVLAT::GetMapCost(int X, int Y, int levind) 00192 { 00193 #if DEBUG 00194 if(levind >= numofadditionalzlevs) 00195 { 00196 SBPL_ERROR("ERROR: GetMapCost invoked at level %d\n", levind); 00197 SBPL_FPRINTF(fDeb, "ERROR: GetMapCost invoked at level %d\n", levind); 00198 return false; 00199 } 00200 #endif 00201 00202 return AddLevelGrid2D[levind][X][Y]; 00203 } 00204 00205 //returns false if robot intersects obstacles or lies outside of the map. 00206 bool EnvironmentNAVXYTHETAMLEVLAT::IsValidConfiguration(int X, int Y, int Theta) 00207 { 00208 //check the base footprint first 00209 if(!EnvironmentNAVXYTHETALAT::IsValidConfiguration(X, Y, Theta)) 00210 return false; 00211 00212 //check the remaining levels now 00213 vector<sbpl_2Dcell_t> footprint; 00214 EnvNAVXYTHETALAT3Dpt_t pose; 00215 00216 //compute continuous pose 00217 pose.x = DISCXY2CONT(X, EnvNAVXYTHETALATCfg.cellsize_m); 00218 pose.y = DISCXY2CONT(Y, EnvNAVXYTHETALATCfg.cellsize_m); 00219 pose.theta = DiscTheta2Cont(Theta, NAVXYTHETALAT_THETADIRS); 00220 00221 //iterate over additional levels 00222 for (int levind=0; levind < numofadditionalzlevs; levind++) 00223 { 00224 00225 //compute footprint cells 00226 CalculateFootprintForPose(pose, &footprint, AddLevelFootprintPolygonV[levind]); 00227 00228 //iterate over all footprint cells 00229 for(int find = 0; find < (int)footprint.size(); find++) 00230 { 00231 int x = footprint.at(find).x; 00232 int y = footprint.at(find).y; 00233 00234 if (x < 0 || x >= EnvNAVXYTHETALATCfg.EnvWidth_c || 00235 y < 0 || y >= EnvNAVXYTHETALATCfg.EnvHeight_c || 00236 AddLevelGrid2D[levind][x][y] >= EnvNAVXYTHETALATCfg.obsthresh) 00237 { 00238 return false; 00239 } 00240 } 00241 } 00242 00243 return true; 00244 00245 } 00246 00247 00248 int EnvironmentNAVXYTHETAMLEVLAT::GetActionCost(int SourceX, int SourceY, int SourceTheta, EnvNAVXYTHETALATAction_t* action) 00249 { 00250 00251 int basecost = EnvironmentNAVXYTHETALAT::GetActionCost(SourceX, SourceY, SourceTheta, action); 00252 00253 if(basecost >= INFINITECOST) 00254 return INFINITECOST; 00255 00256 int addcost = GetActionCostacrossAddLevels(SourceX, SourceY, SourceTheta, action); 00257 00258 return __max(basecost, addcost); 00259 00260 } 00261 00262 00263 int EnvironmentNAVXYTHETAMLEVLAT::GetActionCostacrossAddLevels(int SourceX, int SourceY, int SourceTheta, EnvNAVXYTHETALATAction_t* action) 00264 { 00265 sbpl_2Dcell_t cell; 00266 EnvNAVXYTHETALAT3Dcell_t interm3Dcell; 00267 int i, levelind=-1; 00268 00269 if(!IsValidCell(SourceX, SourceY)) 00270 return INFINITECOST; 00271 if(!IsValidCell(SourceX + action->dX, SourceY + action->dY)) 00272 return INFINITECOST; 00273 00274 //case of no levels 00275 if(numofadditionalzlevs == 0) 00276 return 0; 00277 00278 //iterate through the additional levels 00279 for (levelind=0; levelind < numofadditionalzlevs; levelind++) 00280 { 00281 if(AddLevelGrid2D[levelind][SourceX + action->dX][SourceY + action->dY] >= AddLevel_cost_inscribed_thresh[levelind]) 00282 return INFINITECOST; 00283 } 00284 00285 //need to iterate over discretized center cells and compute cost based on them 00286 unsigned char maxcellcost = 0; 00287 unsigned char* maxcellcostateachlevel = new unsigned char [numofadditionalzlevs]; 00288 for (levelind=0; levelind < numofadditionalzlevs; levelind++) 00289 { 00290 maxcellcostateachlevel[levelind] = 0; 00291 } 00292 00293 00294 for(i = 0; i < (int)action->interm3DcellsV.size() && maxcellcost < EnvNAVXYTHETALATCfg.obsthresh; i++) 00295 { 00296 interm3Dcell = action->interm3DcellsV.at(i); 00297 interm3Dcell.x = interm3Dcell.x + SourceX; 00298 interm3Dcell.y = interm3Dcell.y + SourceY; 00299 00300 if(interm3Dcell.x < 0 || interm3Dcell.x >= EnvNAVXYTHETALATCfg.EnvWidth_c || 00301 interm3Dcell.y < 0 || interm3Dcell.y >= EnvNAVXYTHETALATCfg.EnvHeight_c) 00302 { 00303 maxcellcost = EnvNAVXYTHETALATCfg.obsthresh; 00304 maxcellcostateachlevel[levelind] = EnvNAVXYTHETALATCfg.obsthresh; 00305 break; 00306 } 00307 00308 00309 for (levelind=0; levelind < numofadditionalzlevs; levelind++) 00310 { 00311 maxcellcost = __max(maxcellcost, AddLevelGrid2D[levelind][interm3Dcell.x][interm3Dcell.y]); 00312 maxcellcostateachlevel[levelind] = __max(maxcellcostateachlevel[levelind], AddLevelGrid2D[levelind][interm3Dcell.x][interm3Dcell.y]); 00313 //check that the robot is NOT in the cell at which there is no valid orientation 00314 if(maxcellcostateachlevel[levelind] >= AddLevel_cost_inscribed_thresh[levelind]) 00315 { 00316 maxcellcost = EnvNAVXYTHETALATCfg.obsthresh; 00317 maxcellcostateachlevel[levelind] = EnvNAVXYTHETALATCfg.obsthresh; 00318 break; 00319 } 00320 } 00321 } 00322 00323 //check collisions that for the particular footprint orientation along the action 00324 for (levelind=0; levelind < numofadditionalzlevs && 00325 (int) maxcellcost < EnvNAVXYTHETALATCfg.obsthresh; levelind++) 00326 { 00327 if(AddLevelFootprintPolygonV[levelind].size() > 1 && 00328 (int)maxcellcostateachlevel[levelind] >= AddLevel_cost_possibly_circumscribed_thresh[levelind]) 00329 { 00330 checks++; 00331 00332 //get intersecting cells for this level 00333 vector<sbpl_2Dcell_t>* intersectingcellsV = &AdditionalInfoinActionsV[(unsigned int)action->starttheta][action->aind].intersectingcellsV[levelind]; 00334 for(i = 0; i < (int)intersectingcellsV->size(); i++) 00335 { 00336 //get the cell in the map 00337 cell = intersectingcellsV->at(i); 00338 cell.x = cell.x + SourceX; 00339 cell.y = cell.y + SourceY; 00340 00341 //check validity 00342 if(!IsValidCell(cell.x, cell.y, levelind)) 00343 { 00344 maxcellcost = EnvNAVXYTHETALATCfg.obsthresh; 00345 break; 00346 } 00347 00348 //if(AddLevelGrid2D[levelind][cell.x][cell.y] > maxcellcost) //cost computation changed: cost = max(cost of centers of the robot along action) 00349 // maxcellcost = AddLevelGrid2D[levelind][cell.x][cell.y]; //intersecting cells are only used for collision checking 00350 } 00351 } 00352 } 00353 00354 //no need to max it with grid2D to ensure consistency of h2D since it is done for the base class 00355 00356 //clean up 00357 delete [] maxcellcostateachlevel; 00358 00359 if(maxcellcost >= EnvNAVXYTHETALATCfg.obsthresh) 00360 return INFINITECOST; 00361 else 00362 return action->cost*(((int)maxcellcost)+1); //use cell cost as multiplicative factor 00363 00364 } 00365 00366 //--------------------------------------------------------------------- 00367 00368 00369 //------------debugging functions--------------------------------------------- 00370 00371 00372 //----------------------------------------------------------------------------- 00373 00374 00375 //-----------interface with outside functions----------------------------------- 00376 /* 00377 initialization of additional levels. 0 is the original one. All additional ones will start with index 1 00378 */ 00379 bool EnvironmentNAVXYTHETAMLEVLAT::InitializeAdditionalLevels(int numofadditionalzlevs_in, 00380 const vector<sbpl_2Dpt_t>* perimeterptsV, 00381 unsigned char* cost_inscribed_thresh_in, 00382 unsigned char* cost_possibly_circumscribed_thresh_in) 00383 { 00384 int levelind = -1, xind=-1, yind=-1; 00385 EnvNAVXYTHETALAT3Dpt_t temppose; 00386 temppose.x = 0.0; 00387 temppose.y = 0.0; 00388 temppose.theta = 0.0; 00389 vector<sbpl_2Dcell_t> footprint; 00390 00391 00392 numofadditionalzlevs = numofadditionalzlevs_in; 00393 SBPL_PRINTF("Planning with additional z levels. Number of additional z levels = %d\n", numofadditionalzlevs); 00394 00395 //allocate memory and set FootprintPolygons for additional levels 00396 AddLevelFootprintPolygonV = new vector<sbpl_2Dpt_t> [numofadditionalzlevs]; 00397 for (levelind=0; levelind < numofadditionalzlevs; levelind++) 00398 { 00399 AddLevelFootprintPolygonV[levelind] = perimeterptsV[levelind]; 00400 } 00401 00402 00403 //print out the size of a footprint for each additional level 00404 for(levelind = 0; levelind < numofadditionalzlevs; levelind++) 00405 { 00406 CalculateFootprintForPose(temppose, &footprint, AddLevelFootprintPolygonV[levelind]); 00407 SBPL_PRINTF("number of cells in footprint for additional level %d = %d\n", levelind, (unsigned int)footprint.size()); 00408 } 00409 00410 //compute additional levels action info 00411 SBPL_PRINTF("pre-computing action data for additional levels:\n"); 00412 AdditionalInfoinActionsV = new EnvNAVXYTHETAMLEVLATAddInfoAction_t*[NAVXYTHETALAT_THETADIRS]; 00413 for(int tind = 0; tind < NAVXYTHETALAT_THETADIRS; tind++) 00414 { 00415 SBPL_PRINTF("pre-computing for angle %d out of %d angles\n", tind, NAVXYTHETALAT_THETADIRS); 00416 00417 //compute sourcepose 00418 EnvNAVXYTHETALAT3Dpt_t sourcepose; 00419 sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); 00420 sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETALATCfg.cellsize_m); 00421 sourcepose.theta = DiscTheta2Cont(tind, NAVXYTHETALAT_THETADIRS); 00422 00423 AdditionalInfoinActionsV[tind] = new EnvNAVXYTHETAMLEVLATAddInfoAction_t[EnvNAVXYTHETALATCfg.actionwidth]; 00424 00425 //iterate over actions for each angle 00426 for (int aind = 0; aind < EnvNAVXYTHETALATCfg.actionwidth; aind++) 00427 { 00428 EnvNAVXYTHETALATAction_t* nav3daction = &EnvNAVXYTHETALATCfg.ActionsV[tind][aind]; 00429 00430 //initialize delta variables 00431 AdditionalInfoinActionsV[tind][aind].dX = nav3daction->dX; 00432 AdditionalInfoinActionsV[tind][aind].dY = nav3daction->dY; 00433 AdditionalInfoinActionsV[tind][aind].starttheta = tind; 00434 AdditionalInfoinActionsV[tind][aind].endtheta = nav3daction->endtheta; 00435 00436 //finally, create the footprint for the action for each level 00437 AdditionalInfoinActionsV[tind][aind].intersectingcellsV = new vector<sbpl_2Dcell_t>[numofadditionalzlevs]; 00438 for(levelind = 0; levelind < numofadditionalzlevs; levelind++) 00439 { 00440 //iterate over the trajectory of the robot executing the action 00441 for (int pind = 0; pind < (int)EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV.size(); pind++) 00442 { 00443 00444 //now compute the intersecting cells (for this pose has to be translated by sourcepose.x,sourcepose.y) 00445 EnvNAVXYTHETALAT3Dpt_t pose; 00446 pose = EnvNAVXYTHETALATCfg.ActionsV[tind][aind].intermptV[pind]; 00447 pose.x += sourcepose.x; 00448 pose.y += sourcepose.y; 00449 CalculateFootprintForPose(pose, &AdditionalInfoinActionsV[tind][aind].intersectingcellsV[levelind], AddLevelFootprintPolygonV[levelind]); 00450 00451 } 00452 00453 //remove the source footprint 00454 RemoveSourceFootprint(sourcepose, &AdditionalInfoinActionsV[tind][aind].intersectingcellsV[levelind], AddLevelFootprintPolygonV[levelind]); 00455 00456 } 00457 } 00458 } 00459 00460 //create maps for additional levels and initialize to zeros (freespace) 00461 AddLevelGrid2D = new unsigned char** [numofadditionalzlevs]; 00462 for(levelind = 0; levelind < numofadditionalzlevs; levelind++) 00463 { 00464 AddLevelGrid2D[levelind] = new unsigned char* [EnvNAVXYTHETALATCfg.EnvWidth_c]; 00465 for (xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { 00466 AddLevelGrid2D[levelind][xind] = new unsigned char [EnvNAVXYTHETALATCfg.EnvHeight_c]; 00467 for(yind = 0; yind < EnvNAVXYTHETALATCfg.EnvHeight_c; yind++) { 00468 AddLevelGrid2D[levelind][xind][yind] = 0; 00469 } 00470 } 00471 } 00472 00473 //create inscribed and circumscribed cost thresholds 00474 AddLevel_cost_possibly_circumscribed_thresh = new unsigned char [numofadditionalzlevs]; 00475 AddLevel_cost_inscribed_thresh = new unsigned char [numofadditionalzlevs]; 00476 for(levelind = 0; levelind < numofadditionalzlevs; levelind++) 00477 { 00478 AddLevel_cost_possibly_circumscribed_thresh[levelind] = cost_possibly_circumscribed_thresh_in[levelind]; 00479 AddLevel_cost_inscribed_thresh[levelind] = cost_inscribed_thresh_in[levelind]; 00480 } 00481 00482 return true; 00483 } 00484 00485 //set 2D map for the additional level levind 00486 bool EnvironmentNAVXYTHETAMLEVLAT::Set2DMapforAddLev(const unsigned char* mapdata, int levind) 00487 { 00488 int xind=-1, yind=-1; 00489 00490 if(AddLevelGrid2D == NULL) 00491 { 00492 SBPL_ERROR("ERROR: failed to set2Dmap because the map was not allocated previously\n"); 00493 return false; 00494 } 00495 00496 for (xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { 00497 for(yind = 0; yind < EnvNAVXYTHETALATCfg.EnvHeight_c; yind++) { 00498 AddLevelGrid2D[levind][xind][yind] = mapdata[xind+yind*EnvNAVXYTHETALATCfg.EnvWidth_c]; 00499 } 00500 } 00501 00502 return true; 00503 } 00504 00505 //set 2D map for the additional level levind 00506 //the version of Set2DMapforAddLev that takes newmap as 2D array instead of one linear array 00507 bool EnvironmentNAVXYTHETAMLEVLAT::Set2DMapforAddLev(const unsigned char** NewGrid2D, int levind) 00508 { 00509 int xind=-1, yind=-1; 00510 00511 if(AddLevelGrid2D == NULL) 00512 { 00513 SBPL_ERROR("ERROR: failed to set2Dmap because the map was not allocated previously\n"); 00514 return false; 00515 } 00516 00517 for (xind = 0; xind < EnvNAVXYTHETALATCfg.EnvWidth_c; xind++) { 00518 for(yind = 0; yind < EnvNAVXYTHETALATCfg.EnvHeight_c; yind++) { 00519 AddLevelGrid2D[levind][xind][yind] = NewGrid2D[xind][yind]; 00520 } 00521 } 00522 00523 return true; 00524 } 00525 00526 00527 00528 /* 00529 update the traversability of a cell<x,y> in addtional level zlev (this is not to update basic level) 00530 */ 00531 bool EnvironmentNAVXYTHETAMLEVLAT::UpdateCostinAddLev(int x, int y, unsigned char newcost, int zlev) 00532 { 00533 00534 #if DEBUG 00535 //SBPL_FPRINTF(fDeb, "Cost updated for cell %d %d at level %d from old cost=%d to new cost=%d\n", 00536 x,y,zlev, AddLevelGrid2D[zlev][x][y], newcost); 00537 #endif 00538 00539 AddLevelGrid2D[zlev][x][y] = newcost; 00540 00541 //no need to update heuristics because at this point it is computed solely based on the basic level 00542 00543 return true; 00544 } 00545 00546 00547 //------------------------------------------------------------------------------