$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 00043 00044 00045 //-------------------constructor-------------------------------------------- 00046 EnvironmentNAV2D::EnvironmentNAV2D() 00047 { 00048 EnvNAV2DCfg.obsthresh = ENVNAV2D_DEFAULTOBSTHRESH; 00049 00050 EnvNAV2DCfg.numofdirs = 8; 00051 EnvNAV2D.bInitialized = false; 00052 00053 }; 00054 00055 00056 00057 //-------------------problem specific and local functions--------------------- 00058 00059 00060 static unsigned int inthash(unsigned int key) 00061 { 00062 key += (key << 12); 00063 key ^= (key >> 22); 00064 key += (key << 4); 00065 key ^= (key >> 9); 00066 key += (key << 10); 00067 key ^= (key >> 2); 00068 key += (key << 7); 00069 key ^= (key >> 12); 00070 return key; 00071 } 00072 00073 //examples of hash functions: map state coordinates onto a hash value 00074 //#define GETHASHBIN(X, Y) (Y*WIDTH_Y+X) 00075 //here we have state coord: <X1, X2, X3, X4> 00076 unsigned int EnvironmentNAV2D::GETHASHBIN(unsigned int X1, unsigned int X2) 00077 { 00078 00079 return inthash(inthash(X1)+(inthash(X2)<<1)) & (EnvNAV2D.HashTableSize-1); 00080 } 00081 00082 00083 00084 void EnvironmentNAV2D::PrintHashTableHist() 00085 { 00086 int s0=0, s1=0, s50=0, s100=0, s200=0, s300=0, slarge=0; 00087 00088 for(int j = 0; j < EnvNAV2D.HashTableSize; j++) 00089 { 00090 if((int)EnvNAV2D.Coord2StateIDHashTable[j].size() == 0) 00091 s0++; 00092 else if((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 50) 00093 s1++; 00094 else if((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 100) 00095 s50++; 00096 else if((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 200) 00097 s100++; 00098 else if((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 300) 00099 s200++; 00100 else if((int)EnvNAV2D.Coord2StateIDHashTable[j].size() < 400) 00101 s300++; 00102 else 00103 slarge++; 00104 } 00105 SBPL_PRINTF("hash table histogram: 0:%d, <50:%d, <100:%d, <200:%d, <300:%d, <400:%d >400:%d\n", 00106 s0,s1, s50, s100, s200,s300,slarge); 00107 } 00108 00109 void EnvironmentNAV2D::SetConfiguration(int width, int height, 00110 const unsigned char* mapdata, 00111 int startx, int starty, 00112 int goalx, int goaly) { 00113 EnvNAV2DCfg.EnvWidth_c = width; 00114 EnvNAV2DCfg.EnvHeight_c = height; 00115 EnvNAV2DCfg.StartX_c = startx; 00116 EnvNAV2DCfg.StartY_c = starty; 00117 int x; 00118 00119 if(EnvNAV2DCfg.StartX_c < 0 || EnvNAV2DCfg.StartX_c >= EnvNAV2DCfg.EnvWidth_c) { 00120 SBPL_ERROR("ERROR: illegal start coordinates\n"); 00121 throw new SBPL_Exception(); 00122 } 00123 if(EnvNAV2DCfg.StartY_c < 0 || EnvNAV2DCfg.StartY_c >= EnvNAV2DCfg.EnvHeight_c) { 00124 SBPL_ERROR("ERROR: illegal start coordinates\n"); 00125 throw new SBPL_Exception(); 00126 } 00127 00128 EnvNAV2DCfg.EndX_c = goalx; 00129 EnvNAV2DCfg.EndY_c = goaly; 00130 00131 //allocate the 2D environment 00132 EnvNAV2DCfg.Grid2D = new unsigned char* [EnvNAV2DCfg.EnvWidth_c]; 00133 for (x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { 00134 EnvNAV2DCfg.Grid2D[x] = new unsigned char [EnvNAV2DCfg.EnvHeight_c]; 00135 } 00136 00137 00138 //environment: 00139 if (0 == mapdata) { 00140 for (int y = 0; y < EnvNAV2DCfg.EnvHeight_c; y++) { 00141 for (int x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { 00142 EnvNAV2DCfg.Grid2D[x][y] = 0; 00143 } 00144 } 00145 } 00146 else { 00147 for (int y = 0; y < EnvNAV2DCfg.EnvHeight_c; y++) { 00148 for (int x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { 00149 unsigned char cval = mapdata[x+y*width]; 00150 EnvNAV2DCfg.Grid2D[x][y] = cval; 00151 } 00152 } 00153 } 00154 00155 } 00156 00157 void EnvironmentNAV2D::ReadConfiguration(FILE* fCfg) 00158 { 00159 //read in the configuration of environment and initialize EnvNAV2DCfg structure 00160 char sTemp[1024], sTemp1[1024]; 00161 int dTemp; 00162 int x, y; 00163 00164 //discretization(cells) 00165 if(fscanf(fCfg, "%s", sTemp) != 1){ 00166 SBPL_ERROR("ERROR: ran out of env file early\n"); 00167 throw new SBPL_Exception(); 00168 } 00169 if(fscanf(fCfg, "%s", sTemp) != 1){ 00170 SBPL_ERROR("ERROR: ran out of env file early\n"); 00171 throw new SBPL_Exception(); 00172 } 00173 EnvNAV2DCfg.EnvWidth_c = atoi(sTemp); 00174 if(fscanf(fCfg, "%s", sTemp) != 1){ 00175 SBPL_ERROR("ERROR: ran out of env file early\n"); 00176 throw new SBPL_Exception(); 00177 } 00178 EnvNAV2DCfg.EnvHeight_c = atoi(sTemp); 00179 00180 //obsthresh: 00181 if(fscanf(fCfg, "%s", sTemp) != 1){ 00182 SBPL_ERROR("ERROR: ran out of env file early\n"); 00183 throw new SBPL_Exception(); 00184 } 00185 strcpy(sTemp1, "obsthresh:"); 00186 if(strcmp(sTemp1, sTemp) != 0) 00187 { 00188 SBPL_ERROR("ERROR: configuration file has incorrect format\n"); 00189 SBPL_PRINTF("Expected %s got %s\n", sTemp1, sTemp); 00190 throw new SBPL_Exception(); 00191 } 00192 if(fscanf(fCfg, "%s", sTemp) != 1){ 00193 SBPL_ERROR("ERROR: ran out of env file early\n"); 00194 throw new SBPL_Exception(); 00195 } 00196 EnvNAV2DCfg.obsthresh = (int)(atof(sTemp)); 00197 SBPL_PRINTF("obsthresh = %d\n", EnvNAV2DCfg.obsthresh); 00198 00199 00200 //start(cells): 00201 if(fscanf(fCfg, "%s", sTemp) != 1){ 00202 SBPL_ERROR("ERROR: ran out of env file early\n"); 00203 throw new SBPL_Exception(); 00204 } 00205 if(fscanf(fCfg, "%s", sTemp) != 1){ 00206 SBPL_ERROR("ERROR: ran out of env file early\n"); 00207 throw new SBPL_Exception(); 00208 } 00209 EnvNAV2DCfg.StartX_c = atoi(sTemp); 00210 if(fscanf(fCfg, "%s", sTemp) != 1){ 00211 SBPL_ERROR("ERROR: ran out of env file early\n"); 00212 throw new SBPL_Exception(); 00213 } 00214 EnvNAV2DCfg.StartY_c = atoi(sTemp); 00215 00216 if(EnvNAV2DCfg.StartX_c < 0 || EnvNAV2DCfg.StartX_c >= EnvNAV2DCfg.EnvWidth_c) 00217 { 00218 SBPL_ERROR("ERROR: illegal start coordinates\n"); 00219 throw new SBPL_Exception(); 00220 } 00221 if(EnvNAV2DCfg.StartY_c < 0 || EnvNAV2DCfg.StartY_c >= EnvNAV2DCfg.EnvHeight_c) 00222 { 00223 SBPL_ERROR("ERROR: illegal start coordinates\n"); 00224 throw new SBPL_Exception(); 00225 } 00226 00227 //end(cells): 00228 if(fscanf(fCfg, "%s", sTemp) != 1){ 00229 SBPL_ERROR("ERROR: ran out of env file early\n"); 00230 throw new SBPL_Exception(); 00231 } 00232 if(fscanf(fCfg, "%s", sTemp) != 1){ 00233 SBPL_ERROR("ERROR: ran out of env file early\n"); 00234 throw new SBPL_Exception(); 00235 } 00236 EnvNAV2DCfg.EndX_c = atoi(sTemp); 00237 if(fscanf(fCfg, "%s", sTemp) != 1){ 00238 SBPL_ERROR("ERROR: ran out of env file early\n"); 00239 throw new SBPL_Exception(); 00240 } 00241 EnvNAV2DCfg.EndY_c = atoi(sTemp); 00242 00243 if(EnvNAV2DCfg.EndX_c < 0 || EnvNAV2DCfg.EndX_c >= EnvNAV2DCfg.EnvWidth_c) 00244 { 00245 SBPL_ERROR("ERROR: illegal end coordinates\n"); 00246 throw new SBPL_Exception(); 00247 } 00248 if(EnvNAV2DCfg.EndY_c < 0 || EnvNAV2DCfg.EndY_c >= EnvNAV2DCfg.EnvHeight_c) 00249 { 00250 SBPL_ERROR("ERROR: illegal end coordinates\n"); 00251 throw new SBPL_Exception(); 00252 } 00253 00254 00255 //allocate the 2D environment 00256 EnvNAV2DCfg.Grid2D = new unsigned char* [EnvNAV2DCfg.EnvWidth_c]; 00257 for (x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) 00258 { 00259 EnvNAV2DCfg.Grid2D[x] = new unsigned char [EnvNAV2DCfg.EnvHeight_c]; 00260 } 00261 00262 //environment: 00263 if(fscanf(fCfg, "%s", sTemp) != 1){ 00264 SBPL_ERROR("ERROR: ran out of env file early\n"); 00265 throw new SBPL_Exception(); 00266 } 00267 for (y = 0; y < EnvNAV2DCfg.EnvHeight_c; y++) 00268 for (x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) 00269 { 00270 if(fscanf(fCfg, "%d", &dTemp) != 1) 00271 { 00272 SBPL_ERROR("ERROR: incorrect format of config file\n"); 00273 throw new SBPL_Exception(); 00274 } 00275 EnvNAV2DCfg.Grid2D[x][y] = dTemp; 00276 } 00277 00278 00279 00280 SBPL_PRINTF("start has cost=%d goal has cost=%d\n", EnvNAV2DCfg.Grid2D[EnvNAV2DCfg.StartX_c][EnvNAV2DCfg.StartY_c], EnvNAV2DCfg.Grid2D[EnvNAV2DCfg.EndX_c][EnvNAV2DCfg.EndY_c]); 00281 } 00282 00283 00284 void EnvironmentNAV2D::InitializeEnvConfig() 00285 { 00286 //aditional to configuration file initialization of EnvNAV2DCfg if necessary 00287 00288 /* 00289 //actions 00290 EnvNAV2DCfg.dXY[0][0] = -1; 00291 EnvNAV2DCfg.dXY[0][1] = -1; 00292 EnvNAV2DCfg.dXY[1][0] = -1; 00293 EnvNAV2DCfg.dXY[1][1] = 0; 00294 EnvNAV2DCfg.dXY[2][0] = -1; 00295 EnvNAV2DCfg.dXY[2][1] = 1; 00296 EnvNAV2DCfg.dXY[3][0] = 0; 00297 EnvNAV2DCfg.dXY[3][1] = -1; 00298 EnvNAV2DCfg.dXY[4][0] = 0; 00299 EnvNAV2DCfg.dXY[4][1] = 1; 00300 EnvNAV2DCfg.dXY[5][0] = 1; 00301 EnvNAV2DCfg.dXY[5][1] = -1; 00302 EnvNAV2DCfg.dXY[6][0] = 1; 00303 EnvNAV2DCfg.dXY[6][1] = 0; 00304 EnvNAV2DCfg.dXY[7][0] = 1; 00305 EnvNAV2DCfg.dXY[7][1] = 1; 00306 */ 00307 Computedxy(); 00308 00309 00310 } 00311 00312 void EnvironmentNAV2D::Computedxy() 00313 { 00314 00315 //initialize some constants for 2D search 00316 EnvNAV2DCfg.dx_[0] = 1; EnvNAV2DCfg.dy_[0] = 1; EnvNAV2DCfg.dxintersects_[0][0] = 0; EnvNAV2DCfg.dyintersects_[0][0] = 1; EnvNAV2DCfg.dxintersects_[0][1] = 1; EnvNAV2DCfg.dyintersects_[0][1] = 0; 00317 EnvNAV2DCfg.dx_[1] = 1; EnvNAV2DCfg.dy_[1] = 0; EnvNAV2DCfg.dxintersects_[1][0] = 0; EnvNAV2DCfg.dyintersects_[1][0] = 0; EnvNAV2DCfg.dxintersects_[1][1] = 0; EnvNAV2DCfg.dyintersects_[1][1] = 0; 00318 EnvNAV2DCfg.dx_[2] = 1; EnvNAV2DCfg.dy_[2] = -1; EnvNAV2DCfg.dxintersects_[2][0] = 0; EnvNAV2DCfg.dyintersects_[2][0] = -1; EnvNAV2DCfg.dxintersects_[2][1] = 1; EnvNAV2DCfg.dyintersects_[2][1] = 0; 00319 EnvNAV2DCfg.dx_[3] = 0; EnvNAV2DCfg.dy_[3] = 1; EnvNAV2DCfg.dxintersects_[3][0] = 0; EnvNAV2DCfg.dyintersects_[3][0] = 0; EnvNAV2DCfg.dxintersects_[3][1] = 0; EnvNAV2DCfg.dyintersects_[3][1] = 0; 00320 EnvNAV2DCfg.dx_[4] = 0; EnvNAV2DCfg.dy_[4] = -1; EnvNAV2DCfg.dxintersects_[4][0] = 0; EnvNAV2DCfg.dyintersects_[4][0] = 0; EnvNAV2DCfg.dxintersects_[4][1] = 0; EnvNAV2DCfg.dyintersects_[4][1] = 0; 00321 EnvNAV2DCfg.dx_[5] = -1; EnvNAV2DCfg.dy_[5] = 1; EnvNAV2DCfg.dxintersects_[5][0] = 0; EnvNAV2DCfg.dyintersects_[5][0] = 1; EnvNAV2DCfg.dxintersects_[5][1] = -1; EnvNAV2DCfg.dyintersects_[5][1] = 0; 00322 EnvNAV2DCfg.dx_[6] = -1; EnvNAV2DCfg.dy_[6] = 0; EnvNAV2DCfg.dxintersects_[6][0] = 0; EnvNAV2DCfg.dyintersects_[6][0] = 0; EnvNAV2DCfg.dxintersects_[6][1] = 0; EnvNAV2DCfg.dyintersects_[6][1] = 0; 00323 EnvNAV2DCfg.dx_[7] = -1; EnvNAV2DCfg.dy_[7] = -1; EnvNAV2DCfg.dxintersects_[7][0] = 0; EnvNAV2DCfg.dyintersects_[7][0] = -1; EnvNAV2DCfg.dxintersects_[7][1] = -1; EnvNAV2DCfg.dyintersects_[7][1] = 0; 00324 00325 //Note: these actions have to be starting at 8 and through 15, since they 00326 //get multiplied correspondingly in Dijkstra's search based on index 00327 EnvNAV2DCfg.dx_[8] = 2; EnvNAV2DCfg.dy_[8] = 1; EnvNAV2DCfg.dxintersects_[8][0] = 1; EnvNAV2DCfg.dyintersects_[8][0] = 0; EnvNAV2DCfg.dxintersects_[8][1] = 1; EnvNAV2DCfg.dyintersects_[8][1] = 1; 00328 EnvNAV2DCfg.dx_[9] = 1; EnvNAV2DCfg.dy_[9] = 2; EnvNAV2DCfg.dxintersects_[9][0] = 0; EnvNAV2DCfg.dyintersects_[9][0] = 1; EnvNAV2DCfg.dxintersects_[9][1] = 1; EnvNAV2DCfg.dyintersects_[9][1] = 1; 00329 EnvNAV2DCfg.dx_[10] = -1; EnvNAV2DCfg.dy_[10] = 2; EnvNAV2DCfg.dxintersects_[10][0] = 0; EnvNAV2DCfg.dyintersects_[10][0] = 1; EnvNAV2DCfg.dxintersects_[10][1] = -1; EnvNAV2DCfg.dyintersects_[10][1] = 1; 00330 EnvNAV2DCfg.dx_[11] = -2; EnvNAV2DCfg.dy_[11] = 1; EnvNAV2DCfg.dxintersects_[11][0] = -1; EnvNAV2DCfg.dyintersects_[11][0] = 0; EnvNAV2DCfg.dxintersects_[11][1] = -1; EnvNAV2DCfg.dyintersects_[11][1] = 1; 00331 EnvNAV2DCfg.dx_[12] = -2; EnvNAV2DCfg.dy_[12] = -1; EnvNAV2DCfg.dxintersects_[12][0] = -1; EnvNAV2DCfg.dyintersects_[12][0] = 0; EnvNAV2DCfg.dxintersects_[12][1] = -1; EnvNAV2DCfg.dyintersects_[12][1] = -1; 00332 EnvNAV2DCfg.dx_[13] = -1; EnvNAV2DCfg.dy_[13] = -2; EnvNAV2DCfg.dxintersects_[13][0] = 0; EnvNAV2DCfg.dyintersects_[13][0] = -1; EnvNAV2DCfg.dxintersects_[13][1] = -1; EnvNAV2DCfg.dyintersects_[13][1] = -1; 00333 EnvNAV2DCfg.dx_[14] = 1; EnvNAV2DCfg.dy_[14] = -2; EnvNAV2DCfg.dxintersects_[14][0] = 0; EnvNAV2DCfg.dyintersects_[14][0] = -1; EnvNAV2DCfg.dxintersects_[14][1] = 1; EnvNAV2DCfg.dyintersects_[14][1] = -1; 00334 EnvNAV2DCfg.dx_[15] = 2; EnvNAV2DCfg.dy_[15] = -1; EnvNAV2DCfg.dxintersects_[15][0] = 1; EnvNAV2DCfg.dyintersects_[15][0] = 0; EnvNAV2DCfg.dxintersects_[15][1] = 1; EnvNAV2DCfg.dyintersects_[15][1] = -1; 00335 00336 //compute distances 00337 for(int dind = 0; dind < ENVNAV2D_MAXDIRS; dind++) 00338 { 00339 00340 if(EnvNAV2DCfg.dx_[dind] != 0 && EnvNAV2DCfg.dy_[dind] != 0){ 00341 if(dind <= 7) 00342 EnvNAV2DCfg.dxy_distance_mm_[dind] = (int)(ENVNAV2D_COSTMULT*1.414); //the cost of a diagonal move in millimeters 00343 else 00344 EnvNAV2DCfg.dxy_distance_mm_[dind] = (int)(ENVNAV2D_COSTMULT*2.236); //the cost of a move to 1,2 or 2,1 or so on in millimeters 00345 } 00346 else 00347 EnvNAV2DCfg.dxy_distance_mm_[dind] = ENVNAV2D_COSTMULT; //the cost of a horizontal move in millimeters 00348 } 00349 } 00350 00351 00352 00353 EnvNAV2DHashEntry_t* EnvironmentNAV2D::GetHashEntry(int X, int Y) 00354 { 00355 00356 #if TIME_DEBUG 00357 clock_t currenttime = clock(); 00358 #endif 00359 00360 int binid = GETHASHBIN(X, Y); 00361 00362 #if DEBUG 00363 if ((int)EnvNAV2D.Coord2StateIDHashTable[binid].size() > 500) 00364 { 00365 SBPL_PRINTF("WARNING: Hash table has a bin %d (X=%d Y=%d) of size %d\n", 00366 binid, X, Y, EnvNAV2D.Coord2StateIDHashTable[binid].size()); 00367 00368 PrintHashTableHist(); 00369 } 00370 #endif 00371 00372 //iterate over the states in the bin and select the perfect match 00373 for(int ind = 0; ind < (int)EnvNAV2D.Coord2StateIDHashTable[binid].size(); ind++) 00374 { 00375 if( EnvNAV2D.Coord2StateIDHashTable[binid][ind]->X == X 00376 && EnvNAV2D.Coord2StateIDHashTable[binid][ind]->Y == Y) 00377 { 00378 #if TIME_DEBUG 00379 time_gethash += clock()-currenttime; 00380 #endif 00381 return EnvNAV2D.Coord2StateIDHashTable[binid][ind]; 00382 } 00383 } 00384 00385 #if TIME_DEBUG 00386 time_gethash += clock()-currenttime; 00387 #endif 00388 00389 return NULL; 00390 } 00391 00392 00393 EnvNAV2DHashEntry_t* EnvironmentNAV2D::CreateNewHashEntry(int X, int Y) 00394 { 00395 int i; 00396 00397 #if TIME_DEBUG 00398 clock_t currenttime = clock(); 00399 #endif 00400 00401 EnvNAV2DHashEntry_t* HashEntry = new EnvNAV2DHashEntry_t; 00402 00403 HashEntry->X = X; 00404 HashEntry->Y = Y; 00405 00406 HashEntry->stateID = EnvNAV2D.StateID2CoordTable.size(); 00407 00408 //insert into the tables 00409 EnvNAV2D.StateID2CoordTable.push_back(HashEntry); 00410 00411 00412 //get the hash table bin 00413 i = GETHASHBIN(HashEntry->X, HashEntry->Y); 00414 00415 //insert the entry into the bin 00416 EnvNAV2D.Coord2StateIDHashTable[i].push_back(HashEntry); 00417 00418 //insert into and initialize the mappings 00419 int* entry = new int [NUMOFINDICES_STATEID2IND]; 00420 StateID2IndexMapping.push_back(entry); 00421 for(i = 0; i < NUMOFINDICES_STATEID2IND; i++) 00422 { 00423 StateID2IndexMapping[HashEntry->stateID][i] = -1; 00424 } 00425 00426 if(HashEntry->stateID != (int)StateID2IndexMapping.size()-1) 00427 { 00428 SBPL_ERROR("ERROR in Env... function: last state has incorrect stateID\n"); 00429 throw new SBPL_Exception(); 00430 } 00431 00432 #if TIME_DEBUG 00433 time_createhash += clock()-currenttime; 00434 #endif 00435 00436 return HashEntry; 00437 } 00438 00439 bool EnvironmentNAV2D::IsValidCell(int X, int Y) 00440 { 00441 return (X >= 0 && X < EnvNAV2DCfg.EnvWidth_c && 00442 Y >= 0 && Y < EnvNAV2DCfg.EnvHeight_c && 00443 EnvNAV2DCfg.Grid2D[X][Y] < EnvNAV2DCfg.obsthresh); 00444 } 00445 00446 bool EnvironmentNAV2D::IsWithinMapCell(int X, int Y) 00447 { 00448 return (X >= 0 && X < EnvNAV2DCfg.EnvWidth_c && 00449 Y >= 0 && Y < EnvNAV2DCfg.EnvHeight_c); 00450 } 00451 00452 00453 00454 EnvironmentNAV2D::~EnvironmentNAV2D(){ 00455 if(EnvNAV2D.Coord2StateIDHashTable != NULL){ 00456 delete[] EnvNAV2D.Coord2StateIDHashTable; 00457 } 00458 00459 for(unsigned int i = 0; i < EnvNAV2D.StateID2CoordTable.size(); ++i){ 00460 if(EnvNAV2D.StateID2CoordTable[i] != NULL) 00461 delete EnvNAV2D.StateID2CoordTable[i]; 00462 } 00463 00464 if(EnvNAV2DCfg.Grid2D != NULL){ 00465 for (int x = 0; x < EnvNAV2DCfg.EnvWidth_c; x++) { 00466 if(EnvNAV2DCfg.Grid2D[x] != NULL) 00467 delete[] EnvNAV2DCfg.Grid2D[x]; 00468 } 00469 delete[] EnvNAV2DCfg.Grid2D; 00470 } 00471 00472 } 00473 00474 void EnvironmentNAV2D::InitializeEnvironment() 00475 { 00476 EnvNAV2DHashEntry_t* HashEntry; 00477 00478 //initialize the map from Coord to StateID 00479 EnvNAV2D.HashTableSize = 64*1024; //should be power of two 00480 EnvNAV2D.Coord2StateIDHashTable = new vector<EnvNAV2DHashEntry_t*>[EnvNAV2D.HashTableSize]; 00481 00482 //initialize the map from StateID to Coord 00483 EnvNAV2D.StateID2CoordTable.clear(); 00484 00485 //create start state 00486 if((HashEntry = GetHashEntry(EnvNAV2DCfg.StartX_c, EnvNAV2DCfg.StartY_c)) == NULL) 00487 { 00488 HashEntry = CreateNewHashEntry(EnvNAV2DCfg.StartX_c, EnvNAV2DCfg.StartY_c); 00489 } 00490 EnvNAV2D.startstateid = HashEntry->stateID; 00491 00492 //create goal state 00493 if((HashEntry = GetHashEntry(EnvNAV2DCfg.EndX_c, EnvNAV2DCfg.EndY_c)) == NULL) 00494 { 00495 HashEntry = CreateNewHashEntry(EnvNAV2DCfg.EndX_c, EnvNAV2DCfg.EndY_c); 00496 } 00497 EnvNAV2D.goalstateid = HashEntry->stateID; 00498 00499 EnvNAV2D.bInitialized = true; 00500 } 00501 00502 static int EuclideanDistance(int X1, int Y1, int X2, int Y2) 00503 { 00504 int sqdist = ((X1-X2)*(X1-X2)+(Y1-Y2)*(Y1-Y2)); 00505 double dist = sqrt((double)sqdist); 00506 return (int)(ENVNAV2D_COSTMULT*dist); 00507 00508 } 00509 00510 //generates nNumofNeighs random neighbors of cell <X,Y> at distance nDist_c (measured in cells) 00511 //it will also generate goal if within this distance as an additional neighbor 00512 //bSuccs is set to true if we are computing successor states, otherwise it is Preds 00513 void EnvironmentNAV2D::GetRandomNeighs(int stateID, std::vector<int>* NeighIDV, std::vector<int>* CLowV, int nNumofNeighs, int nDist_c, bool bSuccs) 00514 { 00515 00516 //clear the successor array 00517 NeighIDV->clear(); 00518 CLowV->clear(); 00519 00520 //get X, Y for the states 00521 EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[stateID]; 00522 int X = HashEntry->X; 00523 int Y = HashEntry->Y; 00524 00525 //iterate through random actions 00526 for (int i = 0, nAttempts = 0; i < nNumofNeighs && nAttempts < 5*nNumofNeighs; i++, nAttempts++) 00527 { 00528 int dX = 0; 00529 int dY = 0; 00530 00531 //pick a direction 00532 float fDir = (float)(2*PI_CONST*(((double)rand())/RAND_MAX)); 00533 00534 //compute the successor that result from following this direction until one of the coordinates reaches the desired distance 00535 //decide whether |dX| = dist or |dY| = dist 00536 float fRadius = 0; 00537 if(fabs(cos(fDir)) > fabs(sin(fDir))) 00538 { 00539 fRadius = (float)((nDist_c+0.5)/fabs(cos(fDir))); 00540 } 00541 else 00542 { 00543 fRadius = (float)((nDist_c+0.5)/fabs(sin(fDir))); 00544 } 00545 00546 dX = (int)(fRadius*cos(fDir)); 00547 dY = (int)(fRadius*sin(fDir)); 00548 00549 if((fabs((float)dX) < nDist_c && fabs((float)dY) < nDist_c) || fabs((float)dX) > nDist_c || 00550 fabs((float)dY) > nDist_c) 00551 { 00552 SBPL_ERROR("ERROR in EnvNav2D genneighs function: dX=%d dY=%d\n", dX, dY); 00553 throw new SBPL_Exception(); 00554 } 00555 00556 //get the coords of the state 00557 int newX = X + dX; 00558 int newY = Y + dY; 00559 00560 //skip the invalid cells 00561 if(!IsValidCell(newX, newY)) 00562 { 00563 i--; 00564 continue; 00565 } 00566 00567 //get the state 00568 EnvNAV2DHashEntry_t* OutHashEntry; 00569 if((OutHashEntry = GetHashEntry(newX, newY)) == NULL) 00570 { 00571 //have to create a new entry 00572 OutHashEntry = CreateNewHashEntry(newX, newY); 00573 } 00574 00575 //compute clow 00576 int clow; 00577 if(bSuccs) 00578 clow = GetFromToHeuristic(stateID, OutHashEntry->stateID); 00579 else 00580 clow = GetFromToHeuristic(OutHashEntry->stateID, stateID); 00581 00582 //insert it into the list 00583 NeighIDV->push_back(OutHashEntry->stateID); 00584 CLowV->push_back(clow); 00585 00586 } 00587 00588 //see if the goal/start belongs to the inside area and if yes then add it to Neighs as well 00589 int desX_c = EnvNAV2DCfg.EndX_c; 00590 int desY_c = EnvNAV2DCfg.EndY_c; 00591 int desstateID = EnvNAV2D.goalstateid; 00592 if(bSuccs == false) 00593 { 00594 desX_c = EnvNAV2DCfg.StartX_c; 00595 desY_c = EnvNAV2DCfg.StartY_c; 00596 desstateID = EnvNAV2D.startstateid; 00597 } 00598 //add it if within the distance 00599 if(abs(desX_c - X) <= nDist_c && abs(desY_c - Y) <= nDist_c) 00600 { 00601 //compute clow 00602 int clow; 00603 if(bSuccs) 00604 clow = GetFromToHeuristic(stateID, desstateID); 00605 else 00606 clow = GetFromToHeuristic(desstateID, stateID); 00607 00608 NeighIDV->push_back(desstateID); 00609 CLowV->push_back(clow); 00610 } 00611 } 00612 00613 00614 00615 //------------------------------------------------------------------------------ 00616 00617 //------------------------------Heuristic computation-------------------------- 00618 00619 void EnvironmentNAV2D::ComputeHeuristicValues() 00620 { 00621 //whatever necessary pre-computation of heuristic values is done here 00622 SBPL_PRINTF("Precomputing heuristics...\n"); 00623 00624 00625 00626 SBPL_PRINTF("done\n"); 00627 00628 } 00629 00630 //-----------interface with outside functions----------------------------------- 00631 bool EnvironmentNAV2D::InitializeEnv(const char* sEnvFile) 00632 { 00633 00634 FILE* fCfg = fopen(sEnvFile, "r"); 00635 if(fCfg == NULL) 00636 { 00637 SBPL_ERROR("ERROR: unable to open %s\n", sEnvFile); 00638 throw new SBPL_Exception(); 00639 } 00640 ReadConfiguration(fCfg); 00641 fclose(fCfg); 00642 00643 InitGeneral(); 00644 00645 return true; 00646 } 00647 00648 00649 bool EnvironmentNAV2D::InitializeEnv(int width, int height, 00650 const unsigned char* mapdata, 00651 unsigned char obsthresh) 00652 { 00653 return InitializeEnv(width, height, mapdata, 00654 0, 0, 0, 0, // just use (0,0) for start and goal 00655 obsthresh); 00656 } 00657 00658 00659 bool EnvironmentNAV2D::InitializeEnv(int width, int height, 00660 const unsigned char* mapdata, 00661 int startx, int starty, 00662 int goalx, int goaly, unsigned char obsthresh) 00663 { 00664 00665 SBPL_PRINTF("env: initialized with width=%d height=%d, start=%d %d, goal=%d %d, obsthresh=%d\n", 00666 width, height, startx, starty, goalx, goaly, obsthresh); 00667 00668 EnvNAV2DCfg.obsthresh = obsthresh; 00669 00670 SetConfiguration(width, height, 00671 mapdata, 00672 startx, starty, 00673 goalx, goaly); 00674 00675 InitGeneral(); 00676 00677 return true; 00678 } 00679 00680 00681 bool EnvironmentNAV2D::InitGeneral() { 00682 //Initialize other parameters of the environment 00683 InitializeEnvConfig(); 00684 00685 //initialize Environment 00686 InitializeEnvironment(); 00687 00688 //pre-compute heuristics 00689 ComputeHeuristicValues(); 00690 00691 return true; 00692 } 00693 00694 bool EnvironmentNAV2D::InitializeMDPCfg(MDPConfig *MDPCfg) 00695 { 00696 //initialize MDPCfg with the start and goal ids 00697 MDPCfg->goalstateid = EnvNAV2D.goalstateid; 00698 MDPCfg->startstateid = EnvNAV2D.startstateid; 00699 00700 return true; 00701 } 00702 00703 00704 00705 int EnvironmentNAV2D::GetFromToHeuristic(int FromStateID, int ToStateID) 00706 { 00707 #if USE_HEUR==0 00708 return 0; 00709 #endif 00710 00711 00712 #if DEBUG 00713 if(FromStateID >= (int)EnvNAV2D.StateID2CoordTable.size() 00714 || ToStateID >= (int)EnvNAV2D.StateID2CoordTable.size()) 00715 { 00716 SBPL_ERROR("ERROR in EnvNAV2D... function: stateID illegal\n"); 00717 throw new SBPL_Exception(); 00718 } 00719 #endif 00720 00721 //get X, Y for the state 00722 EnvNAV2DHashEntry_t* FromHashEntry = EnvNAV2D.StateID2CoordTable[FromStateID]; 00723 EnvNAV2DHashEntry_t* ToHashEntry = EnvNAV2D.StateID2CoordTable[ToStateID]; 00724 00725 00726 return EuclideanDistance(FromHashEntry->X, FromHashEntry->Y, ToHashEntry->X, ToHashEntry->Y); 00727 00728 } 00729 00730 00731 int EnvironmentNAV2D::GetGoalHeuristic(int stateID) 00732 { 00733 #if USE_HEUR==0 00734 return 0; 00735 #endif 00736 00737 #if DEBUG 00738 if(stateID >= (int)EnvNAV2D.StateID2CoordTable.size()) 00739 { 00740 SBPL_ERROR("ERROR in EnvNAV2D... function: stateID illegal\n"); 00741 throw new SBPL_Exception(); 00742 } 00743 #endif 00744 00745 00746 //define this function if it used in the planner (heuristic forward search would use it) 00747 return GetFromToHeuristic(stateID, EnvNAV2D.goalstateid); 00748 00749 } 00750 00751 00752 int EnvironmentNAV2D::GetStartHeuristic(int stateID) 00753 { 00754 #if USE_HEUR==0 00755 return 0; 00756 #endif 00757 00758 00759 #if DEBUG 00760 if(stateID >= (int)EnvNAV2D.StateID2CoordTable.size()) 00761 { 00762 SBPL_ERROR("ERROR in EnvNAV2D... function: stateID illegal\n"); 00763 throw new SBPL_Exception(); 00764 } 00765 #endif 00766 00767 00768 //define this function if it used in the planner (heuristic backward search would use it) 00769 return GetFromToHeuristic(EnvNAV2D.startstateid, stateID); 00770 00771 00772 } 00773 00774 00775 00776 void EnvironmentNAV2D::SetAllActionsandAllOutcomes(CMDPSTATE* state) 00777 { 00778 00779 int cost; 00780 00781 #if DEBUG 00782 if(state->StateID >= (int)EnvNAV2D.StateID2CoordTable.size()) 00783 { 00784 SBPL_ERROR("ERROR in Env... function: stateID illegal\n"); 00785 throw new SBPL_Exception(); 00786 } 00787 00788 if((int)state->Actions.size() != 0) 00789 { 00790 SBPL_ERROR("ERROR in Env_setAllActionsandAllOutcomes: actions already exist for the state\n"); 00791 throw new SBPL_Exception(); 00792 } 00793 #endif 00794 00795 00796 //goal state should be absorbing 00797 if(state->StateID == EnvNAV2D.goalstateid) 00798 return; 00799 00800 //get X, Y for the state 00801 EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[state->StateID]; 00802 00803 //iterate through actions 00804 bool bTestBounds = false; 00805 if(HashEntry->X <= 1 || HashEntry->X >= EnvNAV2DCfg.EnvWidth_c-2 || 00806 HashEntry->Y <= 1 || HashEntry->Y >= EnvNAV2DCfg.EnvHeight_c-2) 00807 bTestBounds = true; 00808 for (int aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) 00809 { 00810 int newX = HashEntry->X + EnvNAV2DCfg.dx_[aind]; 00811 int newY = HashEntry->Y + EnvNAV2DCfg.dy_[aind]; 00812 00813 //skip the invalid cells 00814 if(bTestBounds){ 00815 if(!IsValidCell(newX, newY)) 00816 continue; 00817 } 00818 00819 //compute cost multiplier 00820 int costmult = EnvNAV2DCfg.Grid2D[newX][newY]; 00821 //for diagonal move, take max over adjacent cells 00822 if(newX != HashEntry->X && newY != HashEntry->Y && aind <= 7) 00823 { 00824 //check two more cells through which the action goes 00825 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X][newY]); 00826 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[newX][HashEntry->Y]); 00827 } 00828 else if(aind > 7) 00829 { 00830 //check two more cells through which the action goes 00831 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][0]][HashEntry->Y + EnvNAV2DCfg.dyintersects_[aind][0]]); 00832 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][1]][HashEntry->Y + EnvNAV2DCfg.dyintersects_[aind][1]]); 00833 } 00834 00835 00836 //check that it is valid 00837 if(costmult >= EnvNAV2DCfg.obsthresh) 00838 continue; 00839 00840 //otherwise compute the actual cost 00841 cost = (costmult+1)*EnvNAV2DCfg.dxy_distance_mm_[aind]; 00842 00843 //add the action 00844 CMDPACTION* action = state->AddAction(aind); 00845 00846 #if TIME_DEBUG 00847 clock_t currenttime = clock(); 00848 #endif 00849 00850 00851 EnvNAV2DHashEntry_t* OutHashEntry; 00852 if((OutHashEntry = GetHashEntry(newX, newY)) == NULL) 00853 { 00854 //have to create a new entry 00855 OutHashEntry = CreateNewHashEntry(newX, newY); 00856 } 00857 action->AddOutcome(OutHashEntry->stateID, cost, 1.0); 00858 00859 #if TIME_DEBUG 00860 time3_addallout += clock()-currenttime; 00861 #endif 00862 00863 } 00864 } 00865 00866 00867 00868 void EnvironmentNAV2D::SetAllPreds(CMDPSTATE* state) 00869 { 00870 //implement this if the planner needs access to predecessors 00871 00872 SBPL_ERROR("ERROR in EnvNAV2D... function: SetAllPreds is undefined\n"); 00873 throw new SBPL_Exception(); 00874 } 00875 00876 00877 void EnvironmentNAV2D::GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV) 00878 { 00879 int aind; 00880 00881 #if TIME_DEBUG 00882 clock_t currenttime = clock(); 00883 #endif 00884 00885 //clear the successor array 00886 SuccIDV->clear(); 00887 CostV->clear(); 00888 SuccIDV->reserve(EnvNAV2DCfg.numofdirs); 00889 CostV->reserve(EnvNAV2DCfg.numofdirs); 00890 00891 //goal state should be absorbing 00892 if(SourceStateID == EnvNAV2D.goalstateid) 00893 return; 00894 00895 //get X, Y for the state 00896 EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[SourceStateID]; 00897 00898 //iterate through actions 00899 bool bTestBounds = false; 00900 if(HashEntry->X <= 1 || HashEntry->X >= EnvNAV2DCfg.EnvWidth_c-2 || 00901 HashEntry->Y <= 1 || HashEntry->Y >= EnvNAV2DCfg.EnvHeight_c-2) 00902 bTestBounds = true; 00903 for (aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) 00904 { 00905 int newX = HashEntry->X + EnvNAV2DCfg.dx_[aind]; 00906 int newY = HashEntry->Y + EnvNAV2DCfg.dy_[aind]; 00907 00908 //skip the invalid cells 00909 if(bTestBounds){ 00910 if(!IsValidCell(newX, newY)) 00911 continue; 00912 } 00913 00914 int costmult = EnvNAV2DCfg.Grid2D[newX][newY]; 00915 00916 //for diagonal move, take max over adjacent cells 00917 if(newX != HashEntry->X && newY != HashEntry->Y && aind <= 7) 00918 { 00919 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X][newY]); 00920 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[newX][HashEntry->Y]); 00921 } 00922 else if(aind > 7) 00923 { 00924 //check two more cells through which the action goes 00925 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][0]][HashEntry->Y + EnvNAV2DCfg.dyintersects_[aind][0]]); 00926 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][1]][HashEntry->Y + EnvNAV2DCfg.dyintersects_[aind][1]]); 00927 } 00928 00929 00930 //check that it is valid 00931 if(costmult >= EnvNAV2DCfg.obsthresh) 00932 continue; 00933 00934 //otherwise compute the actual cost 00935 int cost = (costmult+1)*EnvNAV2DCfg.dxy_distance_mm_[aind]; 00936 00937 EnvNAV2DHashEntry_t* OutHashEntry; 00938 if((OutHashEntry = GetHashEntry(newX, newY)) == NULL) 00939 { 00940 //have to create a new entry 00941 OutHashEntry = CreateNewHashEntry(newX, newY); 00942 } 00943 00944 SuccIDV->push_back(OutHashEntry->stateID); 00945 CostV->push_back(cost); 00946 } 00947 00948 #if TIME_DEBUG 00949 time_getsuccs += clock()-currenttime; 00950 #endif 00951 00952 } 00953 00954 void EnvironmentNAV2D::GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* CostV) 00955 { 00956 00957 int aind; 00958 00959 #if TIME_DEBUG 00960 clock_t currenttime = clock(); 00961 #endif 00962 00963 //clear the successor array 00964 PredIDV->clear(); 00965 CostV->clear(); 00966 PredIDV->reserve(EnvNAV2DCfg.numofdirs); 00967 CostV->reserve(EnvNAV2DCfg.numofdirs); 00968 00969 //get X, Y for the state 00970 EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[TargetStateID]; 00971 00972 //no predecessors if obstacle 00973 if(EnvNAV2DCfg.Grid2D[HashEntry->X][HashEntry->Y] >= EnvNAV2DCfg.obsthresh) 00974 return; 00975 00976 int targetcostmult = EnvNAV2DCfg.Grid2D[HashEntry->X][HashEntry->Y]; 00977 00978 //iterate through actions 00979 bool bTestBounds = false; 00980 if(HashEntry->X <= 1 || HashEntry->X >= EnvNAV2DCfg.EnvWidth_c-2 || 00981 HashEntry->Y <= 1 || HashEntry->Y >= EnvNAV2DCfg.EnvHeight_c-2) 00982 bTestBounds = true; 00983 for (aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) 00984 { 00985 //the actions are undirected, so we can use the same array of actions as in getsuccs case 00986 int predX = HashEntry->X + EnvNAV2DCfg.dx_[aind]; 00987 int predY = HashEntry->Y + EnvNAV2DCfg.dy_[aind]; 00988 00989 //skip the invalid cells 00990 if(bTestBounds){ 00991 if(!IsValidCell(predX, predY)) 00992 continue; 00993 } 00994 00995 //compute costmult 00996 int costmult = targetcostmult; 00997 //for diagonal move, take max over adjacent cells 00998 if(predX != HashEntry->X && predY != HashEntry->Y && aind <= 7) 00999 { 01000 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X][predY]); 01001 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[predX][HashEntry->Y]); 01002 } 01003 else if(aind > 7) 01004 { 01005 //check two more cells through which the action goes 01006 //since actions are undirected, we don't have to figure out what are the intersecting cells on moving from <predX,predY> to <X,Y>. 01007 //it is the same cells as moving from <X,Y> to <predX,predY>, which is action aind 01008 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][0]][HashEntry->Y + EnvNAV2DCfg.dyintersects_[aind][0]]); 01009 costmult = __max(costmult, EnvNAV2DCfg.Grid2D[HashEntry->X + EnvNAV2DCfg.dxintersects_[aind][1]][HashEntry->Y + EnvNAV2DCfg.dyintersects_[aind][1]]); 01010 } 01011 01012 //check that it is valid 01013 if(costmult >= EnvNAV2DCfg.obsthresh) 01014 continue; 01015 01016 //otherwise compute the actual cost (once again we use the fact that actions are undirected to determine the cost) 01017 int cost = (costmult+1)*EnvNAV2DCfg.dxy_distance_mm_[aind]; 01018 01019 EnvNAV2DHashEntry_t* OutHashEntry; 01020 if((OutHashEntry = GetHashEntry(predX, predY)) == NULL) 01021 { 01022 //have to create a new entry 01023 OutHashEntry = CreateNewHashEntry(predX, predY); 01024 } 01025 01026 01027 PredIDV->push_back(OutHashEntry->stateID); 01028 CostV->push_back(cost); 01029 } 01030 01031 #if TIME_DEBUG 01032 time_getsuccs += clock()-currenttime; 01033 #endif 01034 01035 01036 } 01037 01038 01039 01040 int EnvironmentNAV2D::SizeofCreatedEnv() 01041 { 01042 return (int)EnvNAV2D.StateID2CoordTable.size(); 01043 01044 } 01045 01046 void EnvironmentNAV2D::PrintState(int stateID, bool bVerbose, FILE* fOut /*=NULL*/) 01047 { 01048 #if DEBUG 01049 if(stateID >= (int)EnvNAV2D.StateID2CoordTable.size()) 01050 { 01051 SBPL_ERROR("ERROR in EnvNAV2D... function: stateID illegal (2)\n"); 01052 throw new SBPL_Exception(); 01053 } 01054 #endif 01055 01056 if(fOut == NULL) 01057 fOut = stdout; 01058 01059 EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[stateID]; 01060 01061 if(stateID == EnvNAV2D.goalstateid && bVerbose) 01062 { 01063 SBPL_FPRINTF(fOut, "the state is a goal state\n"); 01064 } 01065 01066 if(bVerbose) 01067 SBPL_FPRINTF(fOut, "X=%d Y=%d\n", HashEntry->X, HashEntry->Y); 01068 else 01069 SBPL_FPRINTF(fOut, "%d %d\n", HashEntry->X, HashEntry->Y); 01070 01071 } 01072 01073 void EnvironmentNAV2D::GetCoordFromState(int stateID, int& x, int& y) const { 01074 EnvNAV2DHashEntry_t* HashEntry = EnvNAV2D.StateID2CoordTable[stateID]; 01075 x = HashEntry->X; 01076 y = HashEntry->Y; 01077 } 01078 01079 int EnvironmentNAV2D::GetStateFromCoord(int x, int y) { 01080 01081 EnvNAV2DHashEntry_t* OutHashEntry; 01082 if((OutHashEntry = GetHashEntry(x, y)) == NULL){ 01083 //have to create a new entry 01084 OutHashEntry = CreateNewHashEntry(x, y); 01085 } 01086 return OutHashEntry->stateID; 01087 } 01088 01089 const EnvNAV2DConfig_t* EnvironmentNAV2D::GetEnvNavConfig() { 01090 return &EnvNAV2DCfg; 01091 } 01092 01093 //returns the stateid if success, and -1 otherwise 01094 int EnvironmentNAV2D::SetGoal(int x, int y){ 01095 01096 if(!IsWithinMapCell(x,y)) 01097 { 01098 SBPL_ERROR("ERROR: trying to set a goal cell %d %d that is outside of map\n", x,y); 01099 return -1; 01100 } 01101 01102 if(!IsValidCell(x,y)) 01103 { 01104 SBPL_PRINTF("WARNING: goal cell is invalid\n"); 01105 } 01106 01107 01108 EnvNAV2DHashEntry_t* OutHashEntry; 01109 if((OutHashEntry = GetHashEntry(x, y)) == NULL){ 01110 //have to create a new entry 01111 OutHashEntry = CreateNewHashEntry(x, y); 01112 } 01113 EnvNAV2D.goalstateid = OutHashEntry->stateID; 01114 EnvNAV2DCfg.EndX_c = x; 01115 EnvNAV2DCfg.EndY_c = y; 01116 01117 01118 return EnvNAV2D.goalstateid; 01119 01120 } 01121 01122 01123 void EnvironmentNAV2D::SetGoalTolerance(double tol_x, double tol_y, double tol_theta) 01124 { 01125 /* not used yet */ 01126 } 01127 01128 01129 //returns the stateid if success, and -1 otherwise 01130 int EnvironmentNAV2D::SetStart(int x, int y){ 01131 01132 if(!IsWithinMapCell(x,y)) 01133 { 01134 SBPL_ERROR("ERROR: trying to set a start cell %d %d that is outside of map\n", x,y); 01135 return -1; 01136 } 01137 01138 if(!IsValidCell(x,y)) 01139 { 01140 SBPL_PRINTF("WARNING: start cell is invalid\n"); 01141 } 01142 01143 01144 EnvNAV2DHashEntry_t* OutHashEntry; 01145 if((OutHashEntry = GetHashEntry(x, y)) == NULL){ 01146 //have to create a new entry 01147 OutHashEntry = CreateNewHashEntry(x, y); 01148 } 01149 EnvNAV2D.startstateid = OutHashEntry->stateID; 01150 EnvNAV2DCfg.StartX_c = x; 01151 EnvNAV2DCfg.StartY_c = y; 01152 01153 return EnvNAV2D.startstateid; 01154 01155 } 01156 01157 bool EnvironmentNAV2D::UpdateCost(int x, int y, unsigned char newcost) 01158 { 01159 01160 EnvNAV2DCfg.Grid2D[x][y] = newcost; 01161 01162 return true; 01163 } 01164 01165 01166 void EnvironmentNAV2D::PrintEnv_Config(FILE* fOut) 01167 { 01168 01169 //implement this if the planner needs to print out EnvNAV2D. configuration 01170 01171 SBPL_ERROR("ERROR in EnvNAV2D... function: PrintEnv_Config is undefined\n"); 01172 throw new SBPL_Exception(); 01173 01174 } 01175 01176 void EnvironmentNAV2D::PrintTimeStat(FILE* fOut) 01177 { 01178 01179 #if TIME_DEBUG 01180 SBPL_FPRINTF(fOut, "time3_addallout = %f secs, time_gethash = %f secs, time_createhash = %f secs, time_getsuccs = %f\n", 01181 time3_addallout/(double)CLOCKS_PER_SEC, time_gethash/(double)CLOCKS_PER_SEC, 01182 time_createhash/(double)CLOCKS_PER_SEC, time_getsuccs/(double)CLOCKS_PER_SEC); 01183 #endif 01184 } 01185 01186 01187 void EnvironmentNAV2D::GetPredsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *preds_of_changededgesIDV) 01188 { 01189 nav2dcell_t cell; 01190 int aind; 01191 01192 for(int i = 0; i < (int)changedcellsV->size(); i++) 01193 { 01194 cell = changedcellsV->at(i); 01195 preds_of_changededgesIDV->push_back(GetStateFromCoord(cell.x,cell.y)); 01196 01197 for (aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) 01198 { 01199 //the actions are undirected, so we can use the same array of actions as in getsuccs case 01200 int affx = cell.x + EnvNAV2DCfg.dx_[aind]; 01201 int affy = cell.y + EnvNAV2DCfg.dy_[aind]; 01202 if(affx < 0 || affx >= EnvNAV2DCfg.EnvWidth_c || affy < 0 || affy >= EnvNAV2DCfg.EnvHeight_c) 01203 continue; 01204 preds_of_changededgesIDV->push_back(GetStateFromCoord(affx,affy)); 01205 } 01206 } 01207 } 01208 01209 01210 // identical to GetPredsofChangedEdges except for changing "preds" 01211 // into "succs"... can probably have just one method. 01212 void EnvironmentNAV2D::GetSuccsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *succs_of_changededgesIDV) 01213 { 01214 nav2dcell_t cell; 01215 int aind; 01216 01217 for(int i = 0; i < (int)changedcellsV->size(); i++) 01218 { 01219 cell = changedcellsV->at(i); 01220 succs_of_changededgesIDV->push_back(GetStateFromCoord(cell.x,cell.y)); 01221 for (aind = 0; aind < EnvNAV2DCfg.numofdirs; aind++) 01222 { 01223 int affx = cell.x + EnvNAV2DCfg.dx_[aind]; 01224 int affy = cell.y + EnvNAV2DCfg.dy_[aind]; 01225 if(affx < 0 || affx >= EnvNAV2DCfg.EnvWidth_c || affy < 0 || affy >= EnvNAV2DCfg.EnvHeight_c) 01226 continue; 01227 succs_of_changededgesIDV->push_back(GetStateFromCoord(affx,affy)); 01228 } 01229 } 01230 } 01231 01232 01233 bool EnvironmentNAV2D::IsObstacle(int x, int y) 01234 { 01235 01236 return (EnvNAV2DCfg.Grid2D[x][y] >= EnvNAV2DCfg.obsthresh); 01237 01238 } 01239 01240 unsigned char EnvironmentNAV2D::GetMapCost(int x, int y) 01241 { 01242 return EnvNAV2DCfg.Grid2D[x][y]; 01243 } 01244 01245 01246 01247 void EnvironmentNAV2D::GetEnvParms(int *size_x, int *size_y, int* startx, int* starty, int* goalx, int* goaly, unsigned char* obsthresh) 01248 { 01249 *size_x = EnvNAV2DCfg.EnvWidth_c; 01250 *size_y = EnvNAV2DCfg.EnvHeight_c; 01251 01252 *startx = EnvNAV2DCfg.StartX_c; 01253 *starty = EnvNAV2DCfg.StartY_c; 01254 *goalx = EnvNAV2DCfg.EndX_c; 01255 *goaly = EnvNAV2DCfg.EndY_c; 01256 01257 *obsthresh = EnvNAV2DCfg.obsthresh; 01258 } 01259 01260 bool EnvironmentNAV2D::SetEnvParameter(const char* parameter, int value) 01261 { 01262 01263 if(EnvNAV2D.bInitialized == true) 01264 { 01265 SBPL_ERROR("ERROR: all parameters must be set before initialization of the environment\n"); 01266 return false; 01267 } 01268 01269 SBPL_PRINTF("setting parameter %s to %d\n", parameter, value); 01270 01271 if(strcmp(parameter, "is16connected") == 0) 01272 { 01273 if(value != 0) 01274 EnvNAV2DCfg.numofdirs = 16; 01275 else 01276 EnvNAV2DCfg.numofdirs = 8; 01277 } 01278 else 01279 { 01280 SBPL_ERROR("ERROR: invalid parameter %s\n", parameter); 01281 return false; 01282 } 01283 01284 return true; 01285 } 01286 01287 01288 //returns true if two states meet the same condition - see environment.h for more info 01289 bool EnvironmentNAV2D::AreEquivalent(int StateID1, int StateID2) 01290 { 01291 01292 #if DEBUG 01293 if(StateID1 >= (int)EnvNAV2D.StateID2CoordTable.size() || StateID2 >= (int)EnvNAV2D.StateID2CoordTable.size()) 01294 { 01295 SBPL_ERROR("ERROR in EnvNAV2D... function: stateID illegal (2)\n"); 01296 throw new SBPL_Exception(); 01297 } 01298 #endif 01299 01300 //get X, Y for the states 01301 EnvNAV2DHashEntry_t* HashEntry1 = EnvNAV2D.StateID2CoordTable[StateID1]; 01302 EnvNAV2DHashEntry_t* HashEntry2 = EnvNAV2D.StateID2CoordTable[StateID2]; 01303 01304 if(HashEntry1->X == HashEntry2->X && HashEntry1->Y == HashEntry2->Y) 01305 return true; 01306 01307 return false; 01308 } 01309 01310 //generate succs at some domain-dependent distance - see environment.h for more info 01311 void EnvironmentNAV2D::GetRandomSuccsatDistance(int SourceStateID, std::vector<int>* SuccIDV, std::vector<int>* CLowV) 01312 { 01313 //number of random neighbors 01314 int nNumofNeighs = 10; 01315 //distance at which the neighbors are generated 01316 int nDist_c = 100; 01317 01318 01319 #if DEBUG 01320 if(SourceStateID >= (int)EnvNAV2D.StateID2CoordTable.size()) 01321 { 01322 SBPL_ERROR("ERROR in EnvNAV2DGetRandSuccs... function: stateID illegal\n"); 01323 throw new SBPL_Exception(); 01324 } 01325 #endif 01326 01327 //goal state should be absorbing 01328 if(SourceStateID == EnvNAV2D.goalstateid) 01329 return; 01330 01331 //get the successors 01332 bool bSuccs = true; 01333 GetRandomNeighs(SourceStateID, SuccIDV, CLowV, nNumofNeighs, nDist_c, bSuccs); 01334 01335 } 01336 01337 //generate preds at some domain-dependent distance - see environment.h for more info 01338 void EnvironmentNAV2D::GetRandomPredsatDistance(int TargetStateID, std::vector<int>* PredIDV, std::vector<int>* CLowV) 01339 { 01340 //number of random neighbors 01341 int nNumofNeighs = 10; 01342 //distance at which the neighbors are generated 01343 int nDist_c = 100; 01344 01345 01346 #if DEBUG 01347 if(TargetStateID >= (int)EnvNAV2D.StateID2CoordTable.size()) 01348 { 01349 SBPL_ERROR("ERROR in EnvNAV2DGetRandSuccs... function: stateID illegal\n"); 01350 throw new SBPL_Exception(); 01351 } 01352 #endif 01353 01354 //start state does not have start state 01355 if(TargetStateID == EnvNAV2D.startstateid) 01356 return; 01357 01358 //get the predecessors 01359 bool bSuccs = false; 01360 GetRandomNeighs(TargetStateID, PredIDV, CLowV, nNumofNeighs, nDist_c, bSuccs); 01361 01362 01363 } 01364 01365 //------------------------------------------------------------------------------