$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 #include <ros/ros.h> 00032 #include <sbpl/headers.h> 00033 #include <sbpl_cart_planner/environment_cart_planner.h> 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_cart = 0; 00043 00044 #define XYTHETACART2INDEX(X,Y,THETA,CARTANGLE) (THETA + X*NAVXYTHETACARTLAT_THETADIRS + Y*EnvNAVXYTHETACARTLATCfg.EnvWidth_c*NAVXYTHETACARTLAT_THETADIRS + CARTANGLE*EnvNAVXYTHETACARTLATCfg.EnvWidth_c*EnvNAVXYTHETACARTLATCfg.EnvHeight_c*NAVXYTHETACARTLAT_THETADIRS) 00045 00046 //converts discretized version of angle into continuous (radians) 00047 //maps 0->0, 1->delta, 2->2*delta, ... 00048 double CartDiscTheta2Cont(int nTheta, int NUMOFANGLEVALS) 00049 { 00050 double thetaBinSize = (2*MAX_CART_ANGLE)/(CART_THETADIRS-1); 00051 return -MAX_CART_ANGLE+nTheta*thetaBinSize; 00052 } 00053 00054 //converts continuous (radians) version of angle into discrete 00055 //maps 0->0, [delta/2, 3/2*delta)->1, [3/2*delta, 5/2*delta)->2,... 00056 int CartContTheta2Disc(double fTheta, int NUMOFANGLEVALS) 00057 { 00058 if(fTheta < -MAX_CART_ANGLE) 00059 return 0; 00060 else if (fTheta > MAX_CART_ANGLE) 00061 return (CART_THETADIRS-1); 00062 else 00063 { 00064 double thetaBinSize = (2*MAX_CART_ANGLE)/(CART_THETADIRS-1); 00065 return (int)((fTheta+MAX_CART_ANGLE+thetaBinSize/2.0)/thetaBinSize); 00066 } 00067 } 00068 00069 00070 //-----------------constructors/destructors------------------------------- 00071 EnvironmentNAVXYTHETACARTLATTICE::EnvironmentNAVXYTHETACARTLATTICE(): initialized_(true) 00072 { 00073 EnvNAVXYTHETACARTLATCfg.obsthresh = ENVNAVXYTHETACARTLAT_DEFAULTOBSTHRESH; 00074 EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh = EnvNAVXYTHETACARTLATCfg.obsthresh; //the value that pretty much makes it disabled 00075 EnvNAVXYTHETACARTLATCfg.cost_possibly_circumscribed_thresh = -1; //the value that pretty much makes it disabled 00076 00077 grid2Dsearchfromstart = NULL; 00078 grid2Dsearchfromgoal = NULL; 00079 bNeedtoRecomputeStartHeuristics = true; 00080 bNeedtoRecomputeGoalHeuristics = true; 00081 iteration = 0; 00082 00083 EnvNAVXYTHETACARTLAT.bInitialized = false; 00084 00085 EnvNAVXYTHETACARTLATCfg.actionwidth = NAVXYTHETACARTLAT_DEFAULT_ACTIONWIDTH; 00086 00087 //no memory allocated in cfg yet 00088 EnvNAVXYTHETACARTLATCfg.Grid2D = NULL; 00089 EnvNAVXYTHETACARTLATCfg.ActionsV = NULL; 00090 EnvNAVXYTHETACARTLATCfg.PredActionsV = NULL; 00091 } 00092 00093 EnvironmentNAVXYTHETACARTLATTICE::~EnvironmentNAVXYTHETACARTLATTICE() 00094 { 00095 ROS_DEBUG("Destroying XYTHETACARTLATTICE"); 00096 if(grid2Dsearchfromstart != NULL) 00097 delete grid2Dsearchfromstart; 00098 grid2Dsearchfromstart = NULL; 00099 00100 if(grid2Dsearchfromgoal != NULL) 00101 delete grid2Dsearchfromgoal; 00102 grid2Dsearchfromgoal = NULL; 00103 00104 if(EnvNAVXYTHETACARTLATCfg.Grid2D != NULL) 00105 { 00106 for (int x = 0; x < EnvNAVXYTHETACARTLATCfg.EnvWidth_c; x++) 00107 delete [] EnvNAVXYTHETACARTLATCfg.Grid2D[x]; 00108 delete [] EnvNAVXYTHETACARTLATCfg.Grid2D; 00109 EnvNAVXYTHETACARTLATCfg.Grid2D = NULL; 00110 } 00111 00112 //delete actions 00113 if(EnvNAVXYTHETACARTLATCfg.ActionsV != NULL) 00114 { 00115 for(int tind = 0; tind < NAVXYTHETACARTLAT_THETADIRS; tind++) 00116 delete [] EnvNAVXYTHETACARTLATCfg.ActionsV[tind]; 00117 delete [] EnvNAVXYTHETACARTLATCfg.ActionsV; 00118 EnvNAVXYTHETACARTLATCfg.ActionsV = NULL; 00119 } 00120 if(EnvNAVXYTHETACARTLATCfg.PredActionsV != NULL) 00121 { 00122 delete [] EnvNAVXYTHETACARTLATCfg.PredActionsV; 00123 EnvNAVXYTHETACARTLATCfg.PredActionsV = NULL; 00124 } 00125 } 00126 00127 //--------------------------------------------------------------------- 00128 00129 00130 //-------------------problem specific and local functions--------------------- 00131 00132 00133 static unsigned int inthash(unsigned int key) 00134 { 00135 key += (key << 12); 00136 key ^= (key >> 22); 00137 key += (key << 4); 00138 key ^= (key >> 9); 00139 key += (key << 10); 00140 key ^= (key >> 2); 00141 key += (key << 7); 00142 key ^= (key >> 12); 00143 return key; 00144 } 00145 00146 00147 00148 void EnvironmentNAVXYTHETACARTLATTICE::SetConfiguration(int width, 00149 int height, 00150 const unsigned char* mapdata, 00151 int startx, 00152 int starty, 00153 int starttheta, 00154 int startcartangle, 00155 int goalx, 00156 int goaly, 00157 int goaltheta, 00158 int goalcartangle, 00159 double cellsize_m, 00160 double nominalvel_mpersecs, 00161 double timetoturn45degsinplace_secs, 00162 const vector<sbpl_2Dpt_t> & robot_perimeterV, 00163 const vector<sbpl_2Dpt_t> & cart_perimeterV, 00164 const sbpl_2Dpt_t &cart_offset) 00165 { 00166 EnvNAVXYTHETACARTLATCfg.EnvWidth_c = width; 00167 EnvNAVXYTHETACARTLATCfg.EnvHeight_c = height; 00168 EnvNAVXYTHETACARTLATCfg.StartX_c = startx; 00169 EnvNAVXYTHETACARTLATCfg.StartY_c = starty; 00170 EnvNAVXYTHETACARTLATCfg.StartTheta = starttheta; 00171 EnvNAVXYTHETACARTLATCfg.StartCartAngle = startcartangle; 00172 00173 00174 if(EnvNAVXYTHETACARTLATCfg.StartX_c < 0 || EnvNAVXYTHETACARTLATCfg.StartX_c >= EnvNAVXYTHETACARTLATCfg.EnvWidth_c) { 00175 ROS_ERROR("illegal start coordinates"); 00176 initialized_ = false;; 00177 return; 00178 } 00179 if(EnvNAVXYTHETACARTLATCfg.StartY_c < 0 || EnvNAVXYTHETACARTLATCfg.StartY_c >= EnvNAVXYTHETACARTLATCfg.EnvHeight_c) { 00180 ROS_ERROR("illegal start coordinates"); 00181 initialized_ = false;; 00182 return; 00183 } 00184 if(EnvNAVXYTHETACARTLATCfg.StartTheta < 0 || EnvNAVXYTHETACARTLATCfg.StartTheta >= NAVXYTHETACARTLAT_THETADIRS) { 00185 ROS_ERROR("illegal start coordinates for theta"); 00186 initialized_ = false;; 00187 return; 00188 } 00189 if(EnvNAVXYTHETACARTLATCfg.StartCartAngle < 0 || EnvNAVXYTHETACARTLATCfg.StartCartAngle >= CART_THETADIRS) { 00190 ROS_ERROR("illegal start coordinates for theta"); 00191 initialized_ = false;; 00192 return; 00193 } 00194 00195 EnvNAVXYTHETACARTLATCfg.EndX_c = goalx; 00196 EnvNAVXYTHETACARTLATCfg.EndY_c = goaly; 00197 EnvNAVXYTHETACARTLATCfg.EndTheta = goaltheta; 00198 EnvNAVXYTHETACARTLATCfg.EndCartAngle = goalcartangle; 00199 00200 if(EnvNAVXYTHETACARTLATCfg.EndX_c < 0 || EnvNAVXYTHETACARTLATCfg.EndX_c >= EnvNAVXYTHETACARTLATCfg.EnvWidth_c) { 00201 ROS_ERROR("illegal goal coordinates"); 00202 initialized_ = false;; 00203 return; 00204 } 00205 if(EnvNAVXYTHETACARTLATCfg.EndY_c < 0 || EnvNAVXYTHETACARTLATCfg.EndY_c >= EnvNAVXYTHETACARTLATCfg.EnvHeight_c) { 00206 ROS_ERROR("illegal goal coordinates"); 00207 initialized_ = false;; 00208 return; 00209 } 00210 if(EnvNAVXYTHETACARTLATCfg.EndTheta < 0 || EnvNAVXYTHETACARTLATCfg.EndTheta >= NAVXYTHETACARTLAT_THETADIRS) { 00211 ROS_ERROR("illegal goal coordinates for theta"); 00212 initialized_ = false;; 00213 return; 00214 } 00215 if(EnvNAVXYTHETACARTLATCfg.EndCartAngle < 0 || EnvNAVXYTHETACARTLATCfg.EndCartAngle >= CART_THETADIRS) { 00216 ROS_ERROR("illegal goal coordinates for theta"); 00217 initialized_ = false;; 00218 return; 00219 } 00220 00221 EnvNAVXYTHETACARTLATCfg.FootprintPolygon = robot_perimeterV; 00222 EnvNAVXYTHETACARTLATCfg.CartPolygon = cart_perimeterV; 00223 EnvNAVXYTHETACARTLATCfg.CartOffset = cart_offset; 00224 00225 EnvNAVXYTHETACARTLATCfg.CartCenterOffset.x = 0.0; 00226 EnvNAVXYTHETACARTLATCfg.CartCenterOffset.y = 0.0; 00227 00228 for(unsigned int i= 0; i < cart_perimeterV.size(); i++) 00229 { 00230 EnvNAVXYTHETACARTLATCfg.CartCenterOffset.x += cart_perimeterV[i].x; 00231 EnvNAVXYTHETACARTLATCfg.CartCenterOffset.y += cart_perimeterV[i].y; 00232 } 00233 00234 EnvNAVXYTHETACARTLATCfg.CartCenterOffset.x = EnvNAVXYTHETACARTLATCfg.CartCenterOffset.x/cart_perimeterV.size(); 00235 EnvNAVXYTHETACARTLATCfg.CartCenterOffset.y = EnvNAVXYTHETACARTLATCfg.CartCenterOffset.y/cart_perimeterV.size(); 00236 00237 EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs = nominalvel_mpersecs; 00238 EnvNAVXYTHETACARTLATCfg.cellsize_m = cellsize_m; 00239 EnvNAVXYTHETACARTLATCfg.timetoturn45degsinplace_secs = timetoturn45degsinplace_secs; 00240 00241 00242 //allocate the 2D environment 00243 EnvNAVXYTHETACARTLATCfg.Grid2D = new unsigned char* [EnvNAVXYTHETACARTLATCfg.EnvWidth_c]; 00244 for (int x = 0; x < EnvNAVXYTHETACARTLATCfg.EnvWidth_c; x++) { 00245 EnvNAVXYTHETACARTLATCfg.Grid2D[x] = new unsigned char [EnvNAVXYTHETACARTLATCfg.EnvHeight_c]; 00246 } 00247 00248 //environment: 00249 if (0 == mapdata) { 00250 for (int y = 0; y < EnvNAVXYTHETACARTLATCfg.EnvHeight_c; y++) { 00251 for (int x = 0; x < EnvNAVXYTHETACARTLATCfg.EnvWidth_c; x++) { 00252 EnvNAVXYTHETACARTLATCfg.Grid2D[x][y] = 0; 00253 } 00254 } 00255 } 00256 else { 00257 for (int y = 0; y < EnvNAVXYTHETACARTLATCfg.EnvHeight_c; y++) { 00258 for (int x = 0; x < EnvNAVXYTHETACARTLATCfg.EnvWidth_c; x++) { 00259 EnvNAVXYTHETACARTLATCfg.Grid2D[x][y] = mapdata[x+y*width]; 00260 } 00261 } 00262 } 00263 } 00264 00265 void EnvironmentNAVXYTHETACARTLATTICE::ReadConfiguration(FILE* fCfg) 00266 { 00267 //read in the configuration of environment and initialize EnvNAVXYTHETACARTLATCfg structure 00268 char sTemp[1024], sTemp1[1024]; 00269 int dTemp; 00270 int x, y; 00271 00272 //discretization(cells) 00273 if(fscanf(fCfg, "%s", sTemp) !=1) 00274 { 00275 ROS_ERROR("Incorrect format of config file"); 00276 initialized_ = false; 00277 return; 00278 } 00279 00280 strcpy(sTemp1, "discretization(cells):"); 00281 if(strcmp(sTemp1, sTemp) != 0) 00282 { 00283 ROS_ERROR("configuration file has incorrect format"); 00284 ROS_ERROR("Expected %s got %s", sTemp1, sTemp); 00285 initialized_ = false; 00286 return; 00287 } 00288 00289 if(fscanf(fCfg, "%s", sTemp) != 1) 00290 { 00291 ROS_ERROR("Incorrect format of config file"); 00292 initialized_ = false; 00293 return; 00294 } 00295 00296 EnvNAVXYTHETACARTLATCfg.EnvWidth_c = atoi(sTemp); 00297 if(fscanf(fCfg, "%s", sTemp) != 1) 00298 { 00299 ROS_ERROR("Incorrect format of config file"); 00300 initialized_ = false; 00301 return; 00302 } 00303 00304 EnvNAVXYTHETACARTLATCfg.EnvHeight_c = atoi(sTemp); 00305 00306 //obsthresh: 00307 if(fscanf(fCfg, "%s", sTemp) != 1) 00308 { 00309 ROS_ERROR("Incorrect format of config file"); 00310 initialized_ = false; 00311 return; 00312 } 00313 00314 strcpy(sTemp1, "obsthresh:"); 00315 if(strcmp(sTemp1, sTemp) != 0) 00316 { 00317 ROS_ERROR("Configuration file has incorrect format"); 00318 ROS_ERROR("Expected %s got %s", sTemp1, sTemp); 00319 ROS_ERROR("See existing examples of env files for the right format of heading"); 00320 initialized_ = false;; 00321 return; 00322 } 00323 if(fscanf(fCfg, "%s", sTemp) != 1) 00324 { 00325 ROS_ERROR("Incorrect format of config file"); 00326 initialized_ = false; 00327 return; 00328 } 00329 00330 EnvNAVXYTHETACARTLATCfg.obsthresh = atoi(sTemp); 00331 ROS_INFO("obsthresh = %d", EnvNAVXYTHETACARTLATCfg.obsthresh); 00332 00333 //cost_inscribed_thresh: 00334 if(fscanf(fCfg, "%s", sTemp) != 1) 00335 { 00336 ROS_ERROR("Incorrect format of config file"); 00337 initialized_ = false; 00338 return; 00339 } 00340 00341 strcpy(sTemp1, "cost_inscribed_thresh:"); 00342 if(strcmp(sTemp1, sTemp) != 0) 00343 { 00344 ROS_ERROR("Configuration file has incorrect format"); 00345 ROS_ERROR("Expected %s got %s", sTemp1, sTemp); 00346 ROS_ERROR("See existing examples of env files for the right format of heading"); 00347 initialized_ = false; 00348 return; 00349 } 00350 if(fscanf(fCfg, "%s", sTemp) != 1) 00351 { 00352 ROS_ERROR("Incorrect format of config file"); 00353 initialized_ = false; 00354 return; 00355 } 00356 00357 EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh = atoi(sTemp); 00358 ROS_INFO("cost_inscribed_thresh = %d", EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh); 00359 00360 00361 //cost_possibly_circumscribed_thresh: 00362 if(fscanf(fCfg, "%s", sTemp) != 1) 00363 { 00364 ROS_ERROR("Incorrect format of config file"); 00365 initialized_ = false; 00366 return; 00367 } 00368 00369 strcpy(sTemp1, "cost_possibly_circumscribed_thresh:"); 00370 if(strcmp(sTemp1, sTemp) != 0) 00371 { 00372 ROS_ERROR("Configuration file has incorrect format"); 00373 ROS_ERROR("Expected %s got %s", sTemp1, sTemp); 00374 ROS_ERROR("See existing examples of env files for the right format of heading"); 00375 initialized_ = false;; 00376 return; 00377 } 00378 if(fscanf(fCfg, "%s", sTemp) != 1) 00379 { 00380 ROS_ERROR("Incorrect format of config file"); 00381 initialized_ = false; 00382 return; 00383 } 00384 00385 EnvNAVXYTHETACARTLATCfg.cost_possibly_circumscribed_thresh = atoi(sTemp); 00386 ROS_INFO("cost_possibly_circumscribed_thresh = %d", EnvNAVXYTHETACARTLATCfg.cost_possibly_circumscribed_thresh); 00387 00388 00389 //cellsize 00390 if(fscanf(fCfg, "%s", sTemp) != 1) 00391 { 00392 ROS_ERROR("Incorrect format of config file"); 00393 initialized_ = false; 00394 return; 00395 } 00396 00397 strcpy(sTemp1, "cellsize(meters):"); 00398 if(strcmp(sTemp1, sTemp) != 0) 00399 { 00400 ROS_ERROR("Configuration file has incorrect format"); 00401 ROS_ERROR("Expected %s got %s", sTemp1, sTemp); 00402 initialized_ = false; 00403 return; 00404 } 00405 if(fscanf(fCfg, "%s", sTemp) != 1) 00406 { 00407 ROS_ERROR("incorrect format of config file"); 00408 initialized_ = false; 00409 return; 00410 } 00411 00412 EnvNAVXYTHETACARTLATCfg.cellsize_m = atof(sTemp); 00413 00414 //speeds 00415 if(fscanf(fCfg, "%s", sTemp) != 1) 00416 { 00417 ROS_ERROR("Incorrect format of config file"); 00418 initialized_ = false; 00419 return; 00420 } 00421 00422 strcpy(sTemp1, "nominalvel(mpersecs):"); 00423 if(strcmp(sTemp1, sTemp) != 0) 00424 { 00425 ROS_ERROR("Configuration file has incorrect format"); 00426 ROS_ERROR("Expected %s got %s", sTemp1, sTemp); 00427 initialized_ = false; 00428 return; 00429 } 00430 if(fscanf(fCfg, "%s", sTemp) != 1) 00431 { 00432 ROS_ERROR("Incorrect format of config file"); 00433 initialized_ = false; 00434 return; 00435 } 00436 00437 EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs = atof(sTemp); 00438 if(fscanf(fCfg, "%s", sTemp) != 1) 00439 { 00440 ROS_ERROR("Incorrect format of config file"); 00441 initialized_ = false; 00442 return; 00443 } 00444 00445 strcpy(sTemp1, "timetoturn45degsinplace(secs):"); 00446 if(strcmp(sTemp1, sTemp) != 0) 00447 { 00448 ROS_ERROR("Configuration file has incorrect format"); 00449 ROS_ERROR("Expected %s got %s", sTemp1, sTemp); 00450 initialized_ = false; 00451 return; 00452 } 00453 if(fscanf(fCfg, "%s", sTemp) != 1) 00454 { 00455 ROS_ERROR("Incorrect format of config file"); 00456 initialized_ = false; 00457 return; 00458 } 00459 00460 EnvNAVXYTHETACARTLATCfg.timetoturn45degsinplace_secs = atof(sTemp); 00461 00462 00463 //start(meters,rads): 00464 if(fscanf(fCfg, "%s", sTemp) != 1) 00465 { 00466 ROS_ERROR("Incorrect format of config file"); 00467 initialized_ = false; 00468 return; 00469 } 00470 00471 if(fscanf(fCfg, "%s", sTemp) != 1) 00472 { 00473 ROS_ERROR("Incorrect format of config file"); 00474 initialized_ = false; 00475 return; 00476 } 00477 00478 EnvNAVXYTHETACARTLATCfg.StartX_c = CONTXY2DISC(atof(sTemp),EnvNAVXYTHETACARTLATCfg.cellsize_m); 00479 if(fscanf(fCfg, "%s", sTemp) != 1) 00480 { 00481 ROS_ERROR("Incorrect format of config file"); 00482 initialized_ = false; 00483 return; 00484 } 00485 00486 EnvNAVXYTHETACARTLATCfg.StartY_c = CONTXY2DISC(atof(sTemp),EnvNAVXYTHETACARTLATCfg.cellsize_m); 00487 if(fscanf(fCfg, "%s", sTemp) != 1) 00488 { 00489 ROS_ERROR("Incorrect format of config file"); 00490 initialized_ = false; 00491 return; 00492 } 00493 00494 EnvNAVXYTHETACARTLATCfg.StartTheta = ContTheta2Disc(atof(sTemp), NAVXYTHETACARTLAT_THETADIRS); 00495 if(fscanf(fCfg, "%s", sTemp) != 1) 00496 { 00497 ROS_ERROR("ERROR: incorrect format of config file"); 00498 initialized_ = false; 00499 return; 00500 } 00501 00502 EnvNAVXYTHETACARTLATCfg.StartCartAngle = CartContTheta2Disc(atof(sTemp), CART_THETADIRS); 00503 00504 00505 if(EnvNAVXYTHETACARTLATCfg.StartX_c < 0 || EnvNAVXYTHETACARTLATCfg.StartX_c >= EnvNAVXYTHETACARTLATCfg.EnvWidth_c) 00506 { 00507 ROS_ERROR("Illegal start coordinates"); 00508 initialized_ = false; 00509 return; 00510 } 00511 if(EnvNAVXYTHETACARTLATCfg.StartY_c < 0 || EnvNAVXYTHETACARTLATCfg.StartY_c >= EnvNAVXYTHETACARTLATCfg.EnvHeight_c) 00512 { 00513 ROS_ERROR("Illegal start coordinates"); 00514 initialized_ = false; 00515 return; 00516 } 00517 if(EnvNAVXYTHETACARTLATCfg.StartTheta < 0 || EnvNAVXYTHETACARTLATCfg.StartTheta >= NAVXYTHETACARTLAT_THETADIRS) { 00518 ROS_ERROR("illegal start coordinates for theta"); 00519 initialized_ = false; 00520 return; 00521 } 00522 if(EnvNAVXYTHETACARTLATCfg.StartCartAngle < 0 || EnvNAVXYTHETACARTLATCfg.StartCartAngle >= CART_THETADIRS) { 00523 ROS_ERROR("illegal start coordinates for theta"); 00524 initialized_ = false; 00525 return; 00526 } 00527 00528 //end(meters,rads): 00529 if(fscanf(fCfg, "%s", sTemp) != 1) 00530 { 00531 ROS_ERROR("incorrect format of config file"); 00532 initialized_ = false; 00533 return; 00534 } 00535 00536 if(fscanf(fCfg, "%s", sTemp) != 1) 00537 { 00538 ROS_ERROR("incorrect format of config file"); 00539 initialized_ = false; 00540 return; 00541 } 00542 00543 EnvNAVXYTHETACARTLATCfg.EndX_c = CONTXY2DISC(atof(sTemp),EnvNAVXYTHETACARTLATCfg.cellsize_m); 00544 if(fscanf(fCfg, "%s", sTemp) != 1) 00545 { 00546 ROS_ERROR("incorrect format of config file"); 00547 initialized_ = false; 00548 return; 00549 } 00550 00551 EnvNAVXYTHETACARTLATCfg.EndY_c = CONTXY2DISC(atof(sTemp),EnvNAVXYTHETACARTLATCfg.cellsize_m); 00552 if(fscanf(fCfg, "%s", sTemp) != 1) 00553 { 00554 ROS_ERROR("incorrect format of config file"); 00555 initialized_ = false; 00556 return; 00557 } 00558 00559 EnvNAVXYTHETACARTLATCfg.EndTheta = ContTheta2Disc(atof(sTemp), NAVXYTHETACARTLAT_THETADIRS);; 00560 if(fscanf(fCfg, "%s", sTemp) != 1) 00561 { 00562 ROS_ERROR("incorrect format of config file"); 00563 initialized_ = false; 00564 return; 00565 } 00566 00567 EnvNAVXYTHETACARTLATCfg.EndCartAngle = CartContTheta2Disc(atof(sTemp), CART_THETADIRS);; 00568 00569 if(EnvNAVXYTHETACARTLATCfg.EndX_c < 0 || EnvNAVXYTHETACARTLATCfg.EndX_c >= EnvNAVXYTHETACARTLATCfg.EnvWidth_c) 00570 { 00571 ROS_ERROR("illegal end coordinates"); 00572 initialized_ = false; 00573 return; 00574 } 00575 if(EnvNAVXYTHETACARTLATCfg.EndY_c < 0 || EnvNAVXYTHETACARTLATCfg.EndY_c >= EnvNAVXYTHETACARTLATCfg.EnvHeight_c) 00576 { 00577 ROS_ERROR("illegal end coordinates"); 00578 initialized_ = false; 00579 return; 00580 } 00581 if(EnvNAVXYTHETACARTLATCfg.EndTheta < 0 || EnvNAVXYTHETACARTLATCfg.EndTheta >= NAVXYTHETACARTLAT_THETADIRS) { 00582 ROS_ERROR("illegal goal coordinates for theta"); 00583 initialized_ = false; 00584 return; 00585 } 00586 if(EnvNAVXYTHETACARTLATCfg.EndCartAngle < 0 || EnvNAVXYTHETACARTLATCfg.EndCartAngle >= CART_THETADIRS) { 00587 ROS_ERROR("illegal goal coordinates for theta"); 00588 initialized_ = false; 00589 return; 00590 } 00591 00592 //allocate the 2D environment 00593 EnvNAVXYTHETACARTLATCfg.Grid2D = new unsigned char* [EnvNAVXYTHETACARTLATCfg.EnvWidth_c]; 00594 for (x = 0; x < EnvNAVXYTHETACARTLATCfg.EnvWidth_c; x++) 00595 { 00596 EnvNAVXYTHETACARTLATCfg.Grid2D[x] = new unsigned char [EnvNAVXYTHETACARTLATCfg.EnvHeight_c]; 00597 } 00598 00599 //environment: 00600 if(fscanf(fCfg, "%s", sTemp) != 1) 00601 { 00602 ROS_ERROR("incorrect format of config file"); 00603 initialized_ = false; 00604 return; 00605 } 00606 00607 for (y = 0; y < EnvNAVXYTHETACARTLATCfg.EnvHeight_c; y++) 00608 for (x = 0; x < EnvNAVXYTHETACARTLATCfg.EnvWidth_c; x++) 00609 { 00610 if(fscanf(fCfg, "%d", &dTemp) != 1) 00611 { 00612 ROS_ERROR("incorrect format of config file"); 00613 initialized_ = false; 00614 return; 00615 } 00616 EnvNAVXYTHETACARTLATCfg.Grid2D[x][y] = dTemp; 00617 } 00618 } 00619 00620 bool EnvironmentNAVXYTHETACARTLATTICE::ReadinCell(EnvNAVXYTHETACARTLAT3Dcell_t* cell, FILE* fIn) 00621 { 00622 char sTemp[60]; 00623 00624 if(fscanf(fIn, "%s", sTemp) == 0) 00625 return false; 00626 cell->x = atoi(sTemp); 00627 if(fscanf(fIn, "%s", sTemp) == 0) 00628 return false; 00629 cell->y = atoi(sTemp); 00630 if(fscanf(fIn, "%s", sTemp) == 0) 00631 return false; 00632 cell->theta = atoi(sTemp); 00633 //normalize the angle 00634 cell->theta = NORMALIZEDISCTHETA(cell->theta, NAVXYTHETACARTLAT_THETADIRS); 00635 00636 if(fscanf(fIn, "%s", sTemp) == 0) 00637 return false; 00638 cell->cartangle = atoi(sTemp); 00639 //normalize the angle 00640 // cell->cartangle = NORMALIZEDISCTHETA(cell->cartangle, CART_THETADIRS); 00641 00642 return true; 00643 } 00644 00645 bool EnvironmentNAVXYTHETACARTLATTICE::ReadinPose(EnvNAVXYTHETACARTLAT3Dpt_t* pose, FILE* fIn) 00646 { 00647 char sTemp[60]; 00648 00649 if(fscanf(fIn, "%s", sTemp) == 0) 00650 return false; 00651 pose->x = atof(sTemp); 00652 if(fscanf(fIn, "%s", sTemp) == 0) 00653 return false; 00654 pose->y = atof(sTemp); 00655 00656 if(fscanf(fIn, "%s", sTemp) == 0) 00657 return false; 00658 pose->theta = atof(sTemp); 00659 pose->theta = normalizeAngle(pose->theta); 00660 00661 if(fscanf(fIn, "%s", sTemp) == 0) 00662 return false; 00663 pose->cartangle = atof(sTemp); 00664 00665 return true; 00666 } 00667 00668 bool EnvironmentNAVXYTHETACARTLATTICE::ReadinMotionPrimitive(SBPL_xythetacart_mprimitive* pMotPrim, FILE* fIn) 00669 { 00670 char sTemp[1024]; 00671 int dTemp; 00672 char sExpected[1024]; 00673 int numofIntermPoses; 00674 00675 //read in actionID 00676 strcpy(sExpected, "primID:"); 00677 if(fscanf(fIn, "%s", sTemp) == 0) 00678 return false; 00679 if(strcmp(sTemp, sExpected) != 0){ 00680 ROS_ERROR("expected %s but got %s", sExpected, sTemp); 00681 return false; 00682 } 00683 if(fscanf(fIn, "%d", &pMotPrim->motprimID) != 1) 00684 return false; 00685 00686 //read in start angle 00687 strcpy(sExpected, "startangle_c:"); 00688 if(fscanf(fIn, "%s", sTemp) == 0) 00689 return false; 00690 if(strcmp(sTemp, sExpected) != 0){ 00691 ROS_ERROR("expected %s but got %s", sExpected, sTemp); 00692 return false; 00693 } 00694 if(fscanf(fIn, "%d", &dTemp) == 0) 00695 { 00696 ROS_ERROR("ERROR reading startangle"); 00697 return false; 00698 } 00699 pMotPrim->starttheta_c = dTemp; 00700 00701 //read in end pose 00702 strcpy(sExpected, "endpose_c:"); 00703 if(fscanf(fIn, "%s", sTemp) == 0) 00704 return false; 00705 if(strcmp(sTemp, sExpected) != 0){ 00706 ROS_ERROR("expected %s but got %s", sExpected, sTemp); 00707 return false; 00708 } 00709 00710 if(ReadinCell(&pMotPrim->endcell, fIn) == false){ 00711 ROS_ERROR("failed to read in endsearchpose"); 00712 return false; 00713 } 00714 00715 //read in action cost 00716 strcpy(sExpected, "additionalactioncostmult:"); 00717 if(fscanf(fIn, "%s", sTemp) == 0) 00718 return false; 00719 if(strcmp(sTemp, sExpected) != 0){ 00720 ROS_ERROR("expected %s but got %s", sExpected, sTemp); 00721 return false; 00722 } 00723 if(fscanf(fIn, "%d", &dTemp) != 1) 00724 return false; 00725 pMotPrim->additionalactioncostmult = dTemp; 00726 00727 //read in intermediate poses 00728 strcpy(sExpected, "intermediateposes:"); 00729 if(fscanf(fIn, "%s", sTemp) == 0) 00730 return false; 00731 if(strcmp(sTemp, sExpected) != 0){ 00732 ROS_ERROR("expected %s but got %s", sExpected, sTemp); 00733 return false; 00734 } 00735 if(fscanf(fIn, "%d", &numofIntermPoses) != 1) 00736 return false; 00737 //all intermposes should be with respect to 0,0 as starting pose since it will be added later and should be done 00738 //after the action is rotated by initial orientation 00739 for(int i = 0; i < numofIntermPoses; i++){ 00740 EnvNAVXYTHETACARTLAT3Dpt_t intermpose; 00741 if(ReadinPose(&intermpose, fIn) == false){ 00742 ROS_ERROR("failed to read in intermediate poses"); 00743 return false; 00744 } 00745 pMotPrim->intermptV.push_back(intermpose); 00746 } 00747 00748 //check that the last pose corresponds correctly to the last pose 00749 EnvNAVXYTHETACARTLAT3Dpt_t sourcepose; 00750 sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 00751 sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 00752 sourcepose.theta = DiscTheta2Cont(pMotPrim->starttheta_c, NAVXYTHETACARTLAT_THETADIRS); 00753 sourcepose.cartangle = CartDiscTheta2Cont(0, CART_THETADIRS); 00754 00755 double mp_endx_m = sourcepose.x + pMotPrim->intermptV[pMotPrim->intermptV.size()-1].x; 00756 double mp_endy_m = sourcepose.y + pMotPrim->intermptV[pMotPrim->intermptV.size()-1].y; 00757 double mp_endtheta_rad = pMotPrim->intermptV[pMotPrim->intermptV.size()-1].theta; 00758 double mp_endcartangle_rad = pMotPrim->intermptV[pMotPrim->intermptV.size()-1].cartangle; 00759 int endx_c = CONTXY2DISC(mp_endx_m, EnvNAVXYTHETACARTLATCfg.cellsize_m); 00760 int endy_c = CONTXY2DISC(mp_endy_m, EnvNAVXYTHETACARTLATCfg.cellsize_m); 00761 int endtheta_c = ContTheta2Disc(mp_endtheta_rad, NAVXYTHETACARTLAT_THETADIRS); 00762 int endcartangle_c = CartContTheta2Disc(mp_endcartangle_rad, CART_THETADIRS); 00763 if(endx_c != pMotPrim->endcell.x || endy_c != pMotPrim->endcell.y || endtheta_c != pMotPrim->endcell.theta || endcartangle_c != pMotPrim->endcell.cartangle) 00764 { 00765 ROS_ERROR("incorrect primitive %d with startangle=%d last interm point %f %f %f %f does not match end pose %d %d %d %d", 00766 pMotPrim->motprimID, pMotPrim->starttheta_c, 00767 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].cartangle, 00768 pMotPrim->endcell.x, pMotPrim->endcell.y,pMotPrim->endcell.theta,pMotPrim->endcell.cartangle); 00769 return false; 00770 } 00771 00772 00773 return true; 00774 } 00775 00776 00777 // TODO - do we need separate angular resolution for cart angle 00778 bool EnvironmentNAVXYTHETACARTLATTICE::ReadMotionPrimitives(FILE* fMotPrims) 00779 { 00780 char sTemp[1024], sExpected[1024]; 00781 float fTemp; 00782 int dTemp; 00783 int totalNumofActions = 0; 00784 00785 ROS_DEBUG("Reading in motion primitives..., this may take some time."); 00786 00787 //read in the resolution 00788 strcpy(sExpected, "resolution_m:"); 00789 if(fscanf(fMotPrims, "%s", sTemp) == 0) 00790 return false; 00791 if(strcmp(sTemp, sExpected) != 0){ 00792 ROS_ERROR("expected %s but got %s", sExpected, sTemp); 00793 return false; 00794 } 00795 if(fscanf(fMotPrims, "%f", &fTemp) == 0) 00796 return false; 00797 if(fabs(fTemp-EnvNAVXYTHETACARTLATCfg.cellsize_m) > ERR_EPS){ 00798 ROS_ERROR("invalid resolution %f (instead of %f) in the dynamics file", 00799 fTemp, EnvNAVXYTHETACARTLATCfg.cellsize_m); 00800 return false; 00801 } 00802 00803 //read in the angular resolution 00804 strcpy(sExpected, "numberofangles:"); 00805 if(fscanf(fMotPrims, "%s", sTemp) == 0) 00806 return false; 00807 if(strcmp(sTemp, sExpected) != 0){ 00808 ROS_ERROR("expected %s but got %s", sExpected, sTemp); 00809 return false; 00810 } 00811 if(fscanf(fMotPrims, "%d", &dTemp) == 0) 00812 return false; 00813 if(dTemp != NAVXYTHETACARTLAT_THETADIRS){ 00814 ROS_ERROR("invalid angular resolution %d angles (instead of %d angles) in the motion primitives file", 00815 dTemp, NAVXYTHETACARTLAT_THETADIRS); 00816 return false; 00817 } 00818 00819 00820 //read in the total number of actions 00821 strcpy(sExpected, "totalnumberofprimitives:"); 00822 if(fscanf(fMotPrims, "%s", sTemp) == 0) 00823 return false; 00824 if(strcmp(sTemp, sExpected) != 0){ 00825 ROS_ERROR("expected %s but got %s", sExpected, sTemp); 00826 return false; 00827 } 00828 if(fscanf(fMotPrims, "%d", &totalNumofActions) == 0){ 00829 return false; 00830 } 00831 00832 for(int i = 0; i < totalNumofActions; i++){ 00833 SBPL_xythetacart_mprimitive motprim; 00834 00835 if(EnvironmentNAVXYTHETACARTLATTICE::ReadinMotionPrimitive(&motprim, fMotPrims) == false) 00836 return false; 00837 00838 EnvNAVXYTHETACARTLATCfg.mprimV.push_back(motprim); 00839 00840 } 00841 ROS_INFO("Done reading motion primitives"); 00842 00843 return true; 00844 } 00845 00846 // TODO - does this need to be filled up 00847 void EnvironmentNAVXYTHETACARTLATTICE::ComputeReplanningDataforAction(EnvNAVXYTHETACARTLATAction_t* action) 00848 { 00849 int j; 00850 00851 //iterate over all the cells involved in the action 00852 EnvNAVXYTHETACARTLAT3Dcell_t startcell3d, endcell3d; 00853 for(int i = 0; i < (int)action->intersectingcellsV.size(); i++) 00854 { 00855 00856 //compute the translated affected search Pose - what state has an outgoing action whose intersecting cell is at 0,0 00857 startcell3d.theta = action->starttheta; 00858 startcell3d.x = - action->intersectingcellsV.at(i).x; 00859 startcell3d.y = - action->intersectingcellsV.at(i).y; 00860 startcell3d.cartangle = action->startcartangle; 00861 00862 00863 //compute the translated affected search Pose - what state has an incoming action whose intersecting cell is at 0,0 00864 endcell3d.theta = NORMALIZEDISCTHETA(action->endtheta, NAVXYTHETACARTLAT_THETADIRS); 00865 endcell3d.x = startcell3d.x + action->dX; 00866 endcell3d.y = startcell3d.y + action->dY; 00867 endcell3d.cartangle = action->endcartangle; 00868 00869 //store the cells if not already there 00870 for(j = 0; j < (int)affectedsuccstatesV.size(); j++) 00871 { 00872 if(affectedsuccstatesV.at(j) == endcell3d) 00873 break; 00874 } 00875 if (j == (int)affectedsuccstatesV.size()) 00876 affectedsuccstatesV.push_back(endcell3d); 00877 00878 for(j = 0; j < (int)affectedpredstatesV.size(); j++) 00879 { 00880 if(affectedpredstatesV.at(j) == startcell3d) 00881 break; 00882 } 00883 if (j == (int)affectedpredstatesV.size()) 00884 affectedpredstatesV.push_back(startcell3d); 00885 00886 }//over intersecting cells 00887 00888 00889 00890 //add the centers since with h2d we are using these in cost computations 00891 //---intersecting cell = origin 00892 //compute the translated affected search Pose - what state has an outgoing action whose intersecting cell is at 0,0 00893 startcell3d.theta = action->starttheta; 00894 startcell3d.x = - 0; 00895 startcell3d.y = - 0; 00896 startcell3d.cartangle = CartContTheta2Disc(0.0, CART_THETADIRS); 00897 00898 //compute the translated affected search Pose - what state has an incoming action whose intersecting cell is at 0,0 00899 endcell3d.theta = NORMALIZEDISCTHETA(action->endtheta, NAVXYTHETACARTLAT_THETADIRS); 00900 endcell3d.x = startcell3d.x + action->dX; 00901 endcell3d.y = startcell3d.y + action->dY; 00902 endcell3d.cartangle = CartContTheta2Disc(0.0, CART_THETADIRS); 00903 00904 //store the cells if not already there 00905 for(j = 0; j < (int)affectedsuccstatesV.size(); j++) 00906 { 00907 if(affectedsuccstatesV.at(j) == endcell3d) 00908 break; 00909 } 00910 if (j == (int)affectedsuccstatesV.size()) 00911 affectedsuccstatesV.push_back(endcell3d); 00912 00913 for(j = 0; j < (int)affectedpredstatesV.size(); j++) 00914 { 00915 if(affectedpredstatesV.at(j) == startcell3d) 00916 break; 00917 } 00918 if (j == (int)affectedpredstatesV.size()) 00919 affectedpredstatesV.push_back(startcell3d); 00920 00921 00922 //---intersecting cell = outcome state 00923 //compute the translated affected search Pose - what state has an outgoing action whose intersecting cell is at 0,0 00924 startcell3d.theta = action->starttheta; 00925 startcell3d.x = - action->dX; 00926 startcell3d.y = - action->dY; 00927 00928 //compute the translated affected search Pose - what state has an incoming action whose intersecting cell is at 0,0 00929 endcell3d.theta = NORMALIZEDISCTHETA(action->endtheta, NAVXYTHETACARTLAT_THETADIRS); 00930 endcell3d.x = startcell3d.x + action->dX; 00931 endcell3d.y = startcell3d.y + action->dY; 00932 00933 for(j = 0; j < (int)affectedsuccstatesV.size(); j++) 00934 { 00935 if(affectedsuccstatesV.at(j) == endcell3d) 00936 break; 00937 } 00938 if (j == (int)affectedsuccstatesV.size()) 00939 affectedsuccstatesV.push_back(endcell3d); 00940 00941 for(j = 0; j < (int)affectedpredstatesV.size(); j++) 00942 { 00943 if(affectedpredstatesV.at(j) == startcell3d) 00944 break; 00945 } 00946 if (j == (int)affectedpredstatesV.size()) 00947 affectedpredstatesV.push_back(startcell3d); 00948 00949 00950 } 00951 00952 // TODO - does this need to be filled up? 00953 //computes all the 3D states whose outgoing actions are potentially affected when cell (0,0) changes its status 00954 //it also does the same for the 3D states whose incoming actions are potentially affected when cell (0,0) changes its status 00955 void EnvironmentNAVXYTHETACARTLATTICE::ComputeReplanningData() 00956 { 00957 00958 //iterate over all actions 00959 //orientations 00960 for(int tind = 0; tind < NAVXYTHETACARTLAT_THETADIRS; tind++) 00961 { 00962 //actions 00963 for(int aind = 0; aind < EnvNAVXYTHETACARTLATCfg.actionwidth; aind++) 00964 { 00965 //compute replanning data for this action 00966 ComputeReplanningDataforAction(&EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind]); 00967 } 00968 } 00969 } 00970 00971 // TODO - this does not seem to be used anymore 00972 //here motionprimitivevector contains actions only for 0 angle 00973 void EnvironmentNAVXYTHETACARTLATTICE::PrecomputeActionswithBaseMotionPrimitive(vector<SBPL_xythetacart_mprimitive>* motionprimitiveV) 00974 { 00975 00976 ROS_INFO("Pre-computing action data using base motion primitives... this may take some time."); 00977 EnvNAVXYTHETACARTLATCfg.ActionsV = new EnvNAVXYTHETACARTLATAction_t* [NAVXYTHETACARTLAT_THETADIRS]; 00978 EnvNAVXYTHETACARTLATCfg.PredActionsV = new vector<EnvNAVXYTHETACARTLATAction_t*> [NAVXYTHETACARTLAT_THETADIRS]; 00979 vector<sbpl_2Dcell_t> footprint; 00980 00981 //iterate over source angles 00982 for(int tind = 0; tind < NAVXYTHETACARTLAT_THETADIRS; tind++) 00983 { 00984 ROS_DEBUG("pre-computing for angle %d out of %d angles", tind, NAVXYTHETACARTLAT_THETADIRS); 00985 EnvNAVXYTHETACARTLATCfg.ActionsV[tind] = new EnvNAVXYTHETACARTLATAction_t[motionprimitiveV->size()]; 00986 00987 //compute sourcepose 00988 EnvNAVXYTHETACARTLAT3Dpt_t sourcepose; 00989 sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 00990 sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 00991 sourcepose.theta = DiscTheta2Cont(tind, NAVXYTHETACARTLAT_THETADIRS); 00992 sourcepose.cartangle = 0.0; 00993 00994 //iterate over motion primitives 00995 for(size_t aind = 0; aind < motionprimitiveV->size(); aind++) 00996 { 00997 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].starttheta = tind; 00998 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].startcartangle = CartContTheta2Disc(0, CART_THETADIRS); 00999 double mp_endx_m = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size()-1].x; 01000 double mp_endy_m = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size()-1].y; 01001 double mp_endtheta_rad = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size()-1].theta; 01002 // double mp_endcartangle_rad = motionprimitiveV->at(aind).intermptV[motionprimitiveV->at(aind).intermptV.size()-1].cartangle; 01003 01004 double endx = sourcepose.x + (mp_endx_m*cos(sourcepose.theta) - mp_endy_m*sin(sourcepose.theta)); 01005 double endy = sourcepose.y + (mp_endx_m*sin(sourcepose.theta) + mp_endy_m*cos(sourcepose.theta)); 01006 01007 int endx_c = CONTXY2DISC(endx, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01008 int endy_c = CONTXY2DISC(endy, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01009 01010 01011 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta = ContTheta2Disc(mp_endtheta_rad+sourcepose.theta, NAVXYTHETACARTLAT_THETADIRS); 01012 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endcartangle = CartContTheta2Disc(0, CART_THETADIRS); 01013 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX = endx_c; 01014 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY = endy_c; 01015 if(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY != 0 || EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX != 0) 01016 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost = (int)(ceil(NAVXYTHETACARTLAT_COSTMULT_MTOMM*EnvNAVXYTHETACARTLATCfg.cellsize_m/EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs* 01017 sqrt((double)(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX*EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX + 01018 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY*EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY)))); 01019 else //cost of turn in place 01020 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost = (int)(NAVXYTHETACARTLAT_COSTMULT_MTOMM* 01021 EnvNAVXYTHETACARTLATCfg.timetoturn45degsinplace_secs*fabs(computeMinUnsignedAngleDiff(mp_endtheta_rad,0))/(PI_CONST/4.0)); 01022 01023 //compute and store interm points as well as intersecting cells 01024 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); 01025 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.clear(); 01026 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].interm3DcellsV.clear(); 01027 EnvNAVXYTHETACARTLAT3Dcell_t previnterm3Dcell; 01028 previnterm3Dcell.theta = previnterm3Dcell.x = previnterm3Dcell.y = 0; 01029 for (int pind = 0; pind < (int)motionprimitiveV->at(aind).intermptV.size(); pind++) 01030 { 01031 EnvNAVXYTHETACARTLAT3Dpt_t intermpt = motionprimitiveV->at(aind).intermptV[pind]; 01032 01033 //rotate it appropriately 01034 double rotx = intermpt.x*cos(sourcepose.theta) - intermpt.y*sin(sourcepose.theta); 01035 double roty = intermpt.x*sin(sourcepose.theta) + intermpt.y*cos(sourcepose.theta); 01036 intermpt.x = rotx; 01037 intermpt.y = roty; 01038 intermpt.theta = normalizeAngle(sourcepose.theta + intermpt.theta); 01039 01040 //store it (they are with reference to 0,0,stattheta (not sourcepose.x,sourcepose.y,starttheta (that is, half-bin)) 01041 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.push_back(intermpt); 01042 01043 //now compute the intersecting cells (for this pose has to be translated by sourcepose.x,sourcepose.y 01044 EnvNAVXYTHETACARTLAT3Dpt_t pose; 01045 pose = intermpt; 01046 pose.x += sourcepose.x; 01047 pose.y += sourcepose.y; 01048 CalculateFootprintForPose(pose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01049 01050 //now also store the intermediate discretized cell if not there already 01051 EnvNAVXYTHETACARTLAT3Dcell_t interm3Dcell; 01052 interm3Dcell.x = CONTXY2DISC(pose.x, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01053 interm3Dcell.y = CONTXY2DISC(pose.y, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01054 interm3Dcell.theta = ContTheta2Disc(pose.theta, NAVXYTHETACARTLAT_THETADIRS); 01055 interm3Dcell.cartangle = CartContTheta2Disc(pose.cartangle, CART_THETADIRS); 01056 if(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].interm3DcellsV.size() == 0 || 01057 previnterm3Dcell.theta != interm3Dcell.theta || previnterm3Dcell.x != interm3Dcell.x || previnterm3Dcell.y != interm3Dcell.y) 01058 { 01059 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].interm3DcellsV.push_back(interm3Dcell); 01060 } 01061 previnterm3Dcell = interm3Dcell; 01062 01063 } 01064 01065 //now remove the source footprint 01066 RemoveSourceFootprint(sourcepose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01067 01068 #if DEBUG 01069 SBPL_FPRINTF(fDeb, "action tind=%d aind=%d: dX=%d dY=%d endtheta=%d (%.2f degs -> %.2f degs) cost=%d (mprim: %.2f %.2f %.2f)", 01070 (int) tind, (int) aind, 01071 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY, 01072 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, sourcepose.theta*180/PI_CONST, 01073 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV[EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.size()-1].theta*180/PI_CONST, 01074 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost, 01075 mp_endx_m, mp_endy_m, mp_endtheta_rad); 01076 #endif 01077 01078 //add to the list of backward actions 01079 int targettheta = EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta; 01080 if (targettheta < 0) 01081 targettheta = targettheta + NAVXYTHETACARTLAT_THETADIRS; 01082 EnvNAVXYTHETACARTLATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind])); 01083 01084 } 01085 } 01086 01087 //set number of actions 01088 EnvNAVXYTHETACARTLATCfg.actionwidth = motionprimitiveV->size(); 01089 01090 01091 //now compute replanning data 01092 ComputeReplanningData(); 01093 01094 ROS_DEBUG("done pre-computing action data based on motion primitives"); 01095 01096 01097 } 01098 01099 01100 //here motionprimitivevector contains actions for all angles 01101 void EnvironmentNAVXYTHETACARTLATTICE::PrecomputeActionswithCompleteMotionPrimitive(vector<SBPL_xythetacart_mprimitive>* motionprimitiveV) 01102 { 01103 01104 ROS_DEBUG("Pre-computing action data using motion primitives for every angle..."); 01105 EnvNAVXYTHETACARTLATCfg.ActionsV = new EnvNAVXYTHETACARTLATAction_t* [NAVXYTHETACARTLAT_THETADIRS]; 01106 EnvNAVXYTHETACARTLATCfg.PredActionsV = new vector<EnvNAVXYTHETACARTLATAction_t*> [NAVXYTHETACARTLAT_THETADIRS]; 01107 vector<sbpl_2Dcell_t> footprint; 01108 01109 if(motionprimitiveV->size()%NAVXYTHETACARTLAT_THETADIRS != 0) 01110 { 01111 ROS_ERROR("ERROR: motionprimitives should be uniform across actions"); 01112 initialized_ = false; 01113 return; 01114 } 01115 01116 EnvNAVXYTHETACARTLATCfg.actionwidth = ((int)motionprimitiveV->size())/NAVXYTHETACARTLAT_THETADIRS; 01117 01118 //iterate over source angles 01119 int maxnumofactions = 0; 01120 for(int tind = 0; tind < NAVXYTHETACARTLAT_THETADIRS; tind++) 01121 { 01122 ROS_DEBUG("Pre-computing for angle %d out of %d angles", tind, NAVXYTHETACARTLAT_THETADIRS); 01123 01124 EnvNAVXYTHETACARTLATCfg.ActionsV[tind] = new EnvNAVXYTHETACARTLATAction_t[EnvNAVXYTHETACARTLATCfg.actionwidth]; 01125 01126 //compute sourcepose 01127 EnvNAVXYTHETACARTLAT3Dpt_t sourcepose; 01128 sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01129 sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01130 sourcepose.theta = DiscTheta2Cont(tind, NAVXYTHETACARTLAT_THETADIRS); 01131 sourcepose.cartangle = CartDiscTheta2Cont(2, CART_THETADIRS); 01132 01133 //iterate over motion primitives 01134 int numofactions = 0; 01135 int aind = -1; 01136 for(int mind = 0; mind < (int)motionprimitiveV->size(); mind++) 01137 { 01138 //find a motion primitive for this angle 01139 if(motionprimitiveV->at(mind).starttheta_c != tind) 01140 continue; 01141 01142 aind++; 01143 numofactions++; 01144 01145 //start angle 01146 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].starttheta = tind; 01147 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].startcartangle = CartContTheta2Disc(0, CART_THETADIRS); 01148 01149 //compute dislocation 01150 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta = motionprimitiveV->at(mind).endcell.theta; 01151 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endcartangle = CartContTheta2Disc(0, CART_THETADIRS); 01152 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX = motionprimitiveV->at(mind).endcell.x; 01153 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY = motionprimitiveV->at(mind).endcell.y; 01154 01155 //compute cost 01156 if(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY != 0 || EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX != 0) 01157 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost = (int)(ceil(NAVXYTHETACARTLAT_COSTMULT_MTOMM*EnvNAVXYTHETACARTLATCfg.cellsize_m/EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs* 01158 sqrt((double)(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX*EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX + 01159 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY*EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY)))); 01160 else //cost of turn in place 01161 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost = (int)(NAVXYTHETACARTLAT_COSTMULT_MTOMM* 01162 EnvNAVXYTHETACARTLATCfg.timetoturn45degsinplace_secs* 01163 fabs(computeMinUnsignedAngleDiff(DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, NAVXYTHETACARTLAT_THETADIRS), 01164 DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].starttheta, NAVXYTHETACARTLAT_THETADIRS)))/(PI_CONST/4.0)); 01165 //use any additional cost multiplier 01166 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost *= motionprimitiveV->at(mind).additionalactioncostmult; 01167 01168 //compute and store interm points as well as intersecting cells 01169 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); 01170 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.clear(); 01171 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].interm3DcellsV.clear(); 01172 EnvNAVXYTHETACARTLAT3Dcell_t previnterm3Dcell; 01173 previnterm3Dcell.theta = 0; 01174 previnterm3Dcell.x = 0; 01175 previnterm3Dcell.y = 0; 01176 previnterm3Dcell.cartangle = CartContTheta2Disc(0, CART_THETADIRS); 01177 ROS_DEBUG("Motion primitive has %d intermediate points for (%d,%d)",(int)motionprimitiveV->at(mind).intermptV.size(),tind,aind); 01178 for (int pind = 0; pind < (int)motionprimitiveV->at(mind).intermptV.size(); pind++) 01179 { 01180 EnvNAVXYTHETACARTLAT3Dpt_t intermpt = motionprimitiveV->at(mind).intermptV[pind]; 01181 01182 //store it (they are with reference to 0,0,stattheta (not sourcepose.x,sourcepose.y,starttheta (that is, half-bin)) 01183 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.push_back(intermpt); 01184 01185 //now compute the intersecting cells (for this pose has to be translated by sourcepose.x,sourcepose.y 01186 EnvNAVXYTHETACARTLAT3Dpt_t pose; 01187 pose = intermpt; 01188 pose.x += sourcepose.x; 01189 pose.y += sourcepose.y; 01190 ROS_DEBUG("Pose for intermediate point %d is: %f %f %f %f",pind,pose.x,pose.y,pose.theta,pose.cartangle); 01191 CalculateFootprintForPose(pose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01192 01193 EnvNAVXYTHETACARTLAT3Dpt_t cart_center_pose = getCartCenter(pose, EnvNAVXYTHETACARTLATCfg.CartCenterOffset); 01194 01195 //now also store the intermediate discretized cell if not there already 01196 EnvNAVXYTHETACARTLAT3Dcell_t interm3Dcell; 01197 interm3Dcell.x = CONTXY2DISC(pose.x, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01198 interm3Dcell.y = CONTXY2DISC(pose.y, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01199 interm3Dcell.theta = ContTheta2Disc(pose.theta, NAVXYTHETACARTLAT_THETADIRS); 01200 interm3Dcell.cartangle = CartContTheta2Disc(pose.cartangle, CART_THETADIRS); 01201 01202 EnvNAVXYTHETACARTLAT3Dcell_t interm3Dcellcart; 01203 interm3Dcellcart.x = CONTXY2DISC(cart_center_pose.x, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01204 interm3Dcellcart.y = CONTXY2DISC(cart_center_pose.y, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01205 interm3Dcellcart.theta = ContTheta2Disc(cart_center_pose.theta, NAVXYTHETACARTLAT_THETADIRS); 01206 interm3Dcellcart.cartangle = CartContTheta2Disc(cart_center_pose.cartangle, CART_THETADIRS); 01207 01208 01209 if(tind == 0 && aind == 0) 01210 ROS_DEBUG("Intermediate point: %d %d %d %d",interm3Dcell.x, interm3Dcell.y, interm3Dcell.theta, interm3Dcell.cartangle); 01211 // if(interm3Dcell.cartangle != 2) 01212 // ROS_ERROR("Intermediate point: %d %d %d %d",interm3Dcell.x, interm3Dcell.y, interm3Dcell.theta, interm3Dcell.cartangle); 01213 01214 if(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].interm3DcellsV.size() == 0 || 01215 previnterm3Dcell.theta != interm3Dcell.theta || previnterm3Dcell.x != interm3Dcell.x || previnterm3Dcell.y != interm3Dcell.y) 01216 { 01217 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].interm3DcellsV.push_back(interm3Dcell); 01218 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].interm3DcellsV.push_back(interm3Dcellcart); 01219 } 01220 previnterm3Dcell = interm3Dcell; 01221 ROS_DEBUG("Intersecting cells have size: %d",(int)EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.size()); 01222 } 01223 /* 01224 std::stringstream ss; 01225 ss << "/tmp/action_" << tind << "_" << aind; 01226 FILE *fid = fopen(ss.str().c_str(),"w"); 01227 for(unsigned int i=0; i < EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.size(); i++) 01228 { 01229 fprintf(fid, "%d %d %.3f %.3f", 01230 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.at(i).x, 01231 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.at(i).y, 01232 DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.at(i).x, EnvNAVXYTHETACARTLATCfg.cellsize_m), 01233 DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.at(i).y, EnvNAVXYTHETACARTLATCfg.cellsize_m)); 01234 } 01235 fclose(fid);*/ 01236 //now remove the source footprint 01237 RemoveSourceFootprint(sourcepose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01238 /* 01239 std::stringstream ss1; 01240 ss1 << "/tmp/actions/action_rf_" << tind << "_" << aind; 01241 FILE *fid2 = fopen(ss1.str().c_str(),"w"); 01242 for(unsigned int i=0; i < EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.size(); i++) 01243 { 01244 fprintf(fid2, "%d %d %.3f %.3f", 01245 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.at(i).x, 01246 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.at(i).y, 01247 DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.at(i).x, EnvNAVXYTHETACARTLATCfg.cellsize_m), 01248 DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.at(i).y, EnvNAVXYTHETACARTLATCfg.cellsize_m)); 01249 } 01250 fclose(fid2);*/ 01251 /* 01252 std::stringstream ss2; 01253 ss2 << "/tmp/actions/action_sf_" << tind << "_" << aind; 01254 FILE *fid3 = fopen(ss2.str().c_str(),"w"); 01255 std::vector<sbpl_2Dcell_t> footprint_source; 01256 if(aind == 0 && tind == 0) 01257 ROS_INFO("Source pose: %f %f %f %f",sourcepose.x,sourcepose.y,sourcepose.theta,sourcepose.cartangle); 01258 CalculateFootprintForPose(sourcepose, &footprint_source); 01259 for(unsigned int i=0; i < footprint_source.size(); i++) 01260 { 01261 fprintf(fid3, "%d %d %.3f %.3f", 01262 footprint_source.at(i).x, 01263 footprint_source.at(i).y, 01264 DISCXY2CONT(footprint_source.at(i).x, EnvNAVXYTHETACARTLATCfg.cellsize_m), 01265 DISCXY2CONT(footprint_source.at(i).y, EnvNAVXYTHETACARTLATCfg.cellsize_m)); 01266 } 01267 fclose(fid3);*/ 01268 01269 01270 #if DEBUG 01271 SBPL_FPRINTF(fDeb, "action tind=%d aind=%d: dX=%d dY=%d endtheta=%d (%.2f degs -> %.2f degs) cost=%d (mprimID %d: %d %d %d) numofintermcells = %d numofintercells=%d", 01272 (int) tind, (int) aind, 01273 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY, 01274 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, 01275 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV[0].theta*180/PI_CONST, 01276 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV[EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.size()-1].theta*180/PI_CONST, 01277 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost, 01278 motionprimitiveV->at(mind).motprimID, 01279 motionprimitiveV->at(mind).endcell.x, motionprimitiveV->at(mind).endcell.y, motionprimitiveV->at(mind).endcell.theta, 01280 (int)EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].interm3DcellsV.size(), 01281 (int)EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.size()); 01282 #endif 01283 01284 //add to the list of backward actions 01285 int targettheta = EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta; 01286 if (targettheta < 0) 01287 targettheta = targettheta + NAVXYTHETACARTLAT_THETADIRS; 01288 EnvNAVXYTHETACARTLATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind])); 01289 01290 } 01291 01292 if(maxnumofactions < numofactions) 01293 maxnumofactions = numofactions; 01294 } 01295 01296 01297 01298 //at this point we don't allow nonuniform number of actions 01299 if(motionprimitiveV->size() != (size_t)(NAVXYTHETACARTLAT_THETADIRS*maxnumofactions)) 01300 { 01301 ROS_ERROR("nonuniform number of actions is not supported (maxnumofactions=%d while motprims=%d thetas=%d", 01302 maxnumofactions, (int)motionprimitiveV->size(), NAVXYTHETACARTLAT_THETADIRS); 01303 initialized_ = false; 01304 return; 01305 } 01306 01307 //now compute replanning data 01308 ComputeReplanningData(); 01309 ROS_INFO("done pre-computing action data based on motion primitives"); 01310 } 01311 01312 void EnvironmentNAVXYTHETACARTLATTICE::PrecomputeActions() 01313 { 01314 01315 //construct list of actions 01316 ROS_DEBUG("Pre-computing action data internally using the motion primitives for a 3D kinematic planning..."); 01317 EnvNAVXYTHETACARTLATCfg.ActionsV = new EnvNAVXYTHETACARTLATAction_t* [NAVXYTHETACARTLAT_THETADIRS]; 01318 EnvNAVXYTHETACARTLATCfg.PredActionsV = new vector<EnvNAVXYTHETACARTLATAction_t*> [NAVXYTHETACARTLAT_THETADIRS]; 01319 vector<sbpl_2Dcell_t> footprint; 01320 //iterate over source angles 01321 for(int tind = 0; tind < NAVXYTHETACARTLAT_THETADIRS; tind++) 01322 { 01323 ROS_DEBUG("processing angle %d", tind); 01324 EnvNAVXYTHETACARTLATCfg.ActionsV[tind] = new EnvNAVXYTHETACARTLATAction_t[EnvNAVXYTHETACARTLATCfg.actionwidth]; 01325 01326 //compute sourcepose 01327 EnvNAVXYTHETACARTLAT3Dpt_t sourcepose; 01328 sourcepose.x = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01329 sourcepose.y = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01330 sourcepose.theta = DiscTheta2Cont(tind, NAVXYTHETACARTLAT_THETADIRS); 01331 01332 //the construction assumes that the robot first turns and then goes along this new theta 01333 int aind = 0; 01334 for(; aind < 3; aind++) 01335 { 01336 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].starttheta = tind; 01337 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta = (tind + aind - 1)%NAVXYTHETACARTLAT_THETADIRS; //-1,0,1 01338 double angle = DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, NAVXYTHETACARTLAT_THETADIRS); 01339 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX = (int)(cos(angle) + 0.5*(cos(angle)>0?1:-1)); 01340 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY = (int)(sin(angle) + 0.5*(sin(angle)>0?1:-1)); 01341 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost = (int)(ceil(NAVXYTHETACARTLAT_COSTMULT_MTOMM*EnvNAVXYTHETACARTLATCfg.cellsize_m/EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs*sqrt((double)(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX*EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX + 01342 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY*EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY)))); 01343 01344 //compute intersecting cells 01345 EnvNAVXYTHETACARTLAT3Dpt_t pose; 01346 pose.x = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01347 pose.y = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01348 pose.theta = angle; 01349 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.clear(); 01350 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); 01351 CalculateFootprintForPose(pose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01352 RemoveSourceFootprint(sourcepose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01353 01354 #if DEBUG 01355 ROS_DEBUG("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d cost=%d", 01356 tind, aind, EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, angle, 01357 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY, 01358 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost); 01359 #endif 01360 01361 //add to the list of backward actions 01362 int targettheta = EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta; 01363 if (targettheta < 0) 01364 targettheta = targettheta + NAVXYTHETACARTLAT_THETADIRS; 01365 EnvNAVXYTHETACARTLATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind])); 01366 01367 } 01368 01369 //decrease and increase angle without movement 01370 aind = 3; 01371 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].starttheta = tind; 01372 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta = tind-1; 01373 if(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta < 0) EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta += NAVXYTHETACARTLAT_THETADIRS; 01374 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX = 0; 01375 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY = 0; 01376 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost = (int)(NAVXYTHETACARTLAT_COSTMULT_MTOMM*EnvNAVXYTHETACARTLATCfg.timetoturn45degsinplace_secs); 01377 01378 //compute intersecting cells 01379 EnvNAVXYTHETACARTLAT3Dpt_t pose; 01380 pose.x = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01381 pose.y = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01382 pose.theta = DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, NAVXYTHETACARTLAT_THETADIRS); 01383 pose.cartangle = CartDiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endcartangle, CART_THETADIRS); 01384 01385 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.clear(); 01386 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); 01387 CalculateFootprintForPose(pose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01388 RemoveSourceFootprint(sourcepose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01389 01390 #if DEBUG 01391 ROS_DEBUG("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d cost=%d", 01392 tind, aind, EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, NAVXYTHETACARTLAT_THETADIRS), 01393 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY, 01394 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost); 01395 #endif 01396 01397 //add to the list of backward actions 01398 int targettheta = EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta; 01399 if (targettheta < 0) 01400 targettheta = targettheta + NAVXYTHETACARTLAT_THETADIRS; 01401 EnvNAVXYTHETACARTLATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind])); 01402 01403 01404 aind = 4; 01405 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].starttheta = tind; 01406 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta = (tind + 1)%NAVXYTHETACARTLAT_THETADIRS; 01407 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX = 0; 01408 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY = 0; 01409 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost = (int)(NAVXYTHETACARTLAT_COSTMULT_MTOMM*EnvNAVXYTHETACARTLATCfg.timetoturn45degsinplace_secs); 01410 01411 //compute intersecting cells 01412 pose.x = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01413 pose.y = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01414 pose.theta = DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, NAVXYTHETACARTLAT_THETADIRS); 01415 pose.cartangle = CartDiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endcartangle, CART_THETADIRS); 01416 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intermptV.clear(); 01417 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV.clear(); 01418 CalculateFootprintForPose(pose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01419 RemoveSourceFootprint(sourcepose, &EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].intersectingcellsV); 01420 01421 01422 #if DEBUG 01423 ROS_DEBUG("action tind=%d aind=%d: endtheta=%d (%f) dX=%d dY=%d cost=%d", 01424 tind, aind, EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta, NAVXYTHETACARTLAT_THETADIRS), 01425 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dX, EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].dY, 01426 EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].cost); 01427 #endif 01428 01429 //add to the list of backward actions 01430 targettheta = EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind].endtheta; 01431 if (targettheta < 0) 01432 targettheta = targettheta + NAVXYTHETACARTLAT_THETADIRS; 01433 EnvNAVXYTHETACARTLATCfg.PredActionsV[targettheta].push_back(&(EnvNAVXYTHETACARTLATCfg.ActionsV[tind][aind])); 01434 01435 } 01436 01437 //now compute replanning data 01438 ComputeReplanningData(); 01439 ROS_INFO("Done pre-computing action data"); 01440 } 01441 01442 void EnvironmentNAVXYTHETACARTLATTICE::InitializeEnvConfig(vector<SBPL_xythetacart_mprimitive>* motionprimitiveV) 01443 { 01444 //aditional to configuration file initialization of EnvNAVXYTHETACARTLATCfg if necessary 01445 01446 //dXY dirs 01447 EnvNAVXYTHETACARTLATCfg.dXY[0][0] = -1; 01448 EnvNAVXYTHETACARTLATCfg.dXY[0][1] = -1; 01449 EnvNAVXYTHETACARTLATCfg.dXY[1][0] = -1; 01450 EnvNAVXYTHETACARTLATCfg.dXY[1][1] = 0; 01451 EnvNAVXYTHETACARTLATCfg.dXY[2][0] = -1; 01452 EnvNAVXYTHETACARTLATCfg.dXY[2][1] = 1; 01453 EnvNAVXYTHETACARTLATCfg.dXY[3][0] = 0; 01454 EnvNAVXYTHETACARTLATCfg.dXY[3][1] = -1; 01455 EnvNAVXYTHETACARTLATCfg.dXY[4][0] = 0; 01456 EnvNAVXYTHETACARTLATCfg.dXY[4][1] = 1; 01457 EnvNAVXYTHETACARTLATCfg.dXY[5][0] = 1; 01458 EnvNAVXYTHETACARTLATCfg.dXY[5][1] = -1; 01459 EnvNAVXYTHETACARTLATCfg.dXY[6][0] = 1; 01460 EnvNAVXYTHETACARTLATCfg.dXY[6][1] = 0; 01461 EnvNAVXYTHETACARTLATCfg.dXY[7][0] = 1; 01462 EnvNAVXYTHETACARTLATCfg.dXY[7][1] = 1; 01463 01464 01465 EnvNAVXYTHETACARTLAT3Dpt_t temppose; 01466 temppose.x = 0.0; 01467 temppose.y = 0.0; 01468 temppose.theta = 0.0; 01469 vector<sbpl_2Dcell_t> footprint; 01470 CalculateFootprintForPose(temppose, &footprint); 01471 ROS_DEBUG("number of cells in footprint of the robot = %zu", footprint.size()); 01472 01473 #if DEBUG 01474 SBPL_FPRINTF(fDeb, "footprint cells (size=%zu):", footprint.size()); 01475 for(int i = 0; i < (int) footprint.size(); i++) 01476 { 01477 SBPL_FPRINTF(fDeb, "%d %d (cont: %.3f %.3f)", footprint.at(i).x, footprint.at(i).y, 01478 DISCXY2CONT(footprint.at(i).x, EnvNAVXYTHETACARTLATCfg.cellsize_m), 01479 DISCXY2CONT(footprint.at(i).y, EnvNAVXYTHETACARTLATCfg.cellsize_m)); 01480 } 01481 #endif 01482 01483 01484 if(motionprimitiveV == NULL) 01485 PrecomputeActions(); 01486 else 01487 PrecomputeActionswithCompleteMotionPrimitive(motionprimitiveV); 01488 01489 01490 } 01491 01492 01493 01494 bool EnvironmentNAVXYTHETACARTLATTICE::IsValidCell(int X, int Y) 01495 { 01496 return (X >= 0 && X < EnvNAVXYTHETACARTLATCfg.EnvWidth_c && 01497 Y >= 0 && Y < EnvNAVXYTHETACARTLATCfg.EnvHeight_c && 01498 EnvNAVXYTHETACARTLATCfg.Grid2D[X][Y] < EnvNAVXYTHETACARTLATCfg.obsthresh); 01499 } 01500 01501 bool EnvironmentNAVXYTHETACARTLATTICE::IsWithinMapCell(int X, int Y) 01502 { 01503 return (X >= 0 && X < EnvNAVXYTHETACARTLATCfg.EnvWidth_c && 01504 Y >= 0 && Y < EnvNAVXYTHETACARTLATCfg.EnvHeight_c); 01505 } 01506 01507 bool EnvironmentNAVXYTHETACARTLATTICE::IsValidConfiguration(int X, int Y, int Theta, int CartAngle) 01508 { 01509 vector<sbpl_2Dcell_t> footprint; 01510 EnvNAVXYTHETACARTLAT3Dpt_t pose; 01511 01512 //compute continuous pose 01513 pose.x = DISCXY2CONT(X, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01514 pose.y = DISCXY2CONT(Y, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01515 pose.theta = DiscTheta2Cont(Theta, NAVXYTHETACARTLAT_THETADIRS); 01516 pose.cartangle = CartDiscTheta2Cont(CartAngle, CART_THETADIRS); 01517 01518 //compute footprint cells 01519 CalculateFootprintForPose(pose, &footprint); 01520 01521 //iterate over all footprint cells 01522 for(int find = 0; find < (int)footprint.size(); find++) 01523 { 01524 int x = footprint.at(find).x; 01525 int y = footprint.at(find).y; 01526 01527 if (x < 0 || x >= EnvNAVXYTHETACARTLATCfg.EnvWidth_c || 01528 y < 0 || y >= EnvNAVXYTHETACARTLATCfg.EnvHeight_c || 01529 EnvNAVXYTHETACARTLATCfg.Grid2D[x][y] >= EnvNAVXYTHETACARTLATCfg.obsthresh) 01530 { 01531 ROS_WARN("Robot configuration %.2f, %.2f, %.2f is invalid, robot/cart system inside obstacle", 01532 pose.x, pose.y, pose.theta); 01533 return false; 01534 } 01535 } 01536 01537 return true; 01538 } 01539 01540 01541 int EnvironmentNAVXYTHETACARTLATTICE::GetActionCost(int SourceX, int SourceY, int SourceTheta, int SourceCartAngle, EnvNAVXYTHETACARTLATAction_t* action) 01542 { 01543 sbpl_2Dcell_t cell; 01544 EnvNAVXYTHETACARTLAT3Dcell_t interm3Dcell; 01545 int i; 01546 01547 //TODO - go over bounding box (minpt and maxpt) to test validity and skip testing boundaries below, also order intersect cells so that the four farthest pts go first 01548 if(!IsValidCell(SourceX, SourceY)) 01549 { 01550 return INFINITECOST; 01551 } 01552 if(!IsValidCell(SourceX + action->dX, SourceY + action->dY)) 01553 { 01554 return INFINITECOST; 01555 } 01556 01557 if(EnvNAVXYTHETACARTLATCfg.Grid2D[SourceX + action->dX][SourceY + action->dY] >= EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh) 01558 { 01559 return INFINITECOST; 01560 } 01561 01562 //need to iterate over discretized center cells and compute cost based on them 01563 unsigned char maxcellcost = 0; 01564 for(i = 0; i < (int)action->interm3DcellsV.size(); i++) 01565 { 01566 interm3Dcell = action->interm3DcellsV.at(i); 01567 interm3Dcell.x = interm3Dcell.x + SourceX; 01568 interm3Dcell.y = interm3Dcell.y + SourceY; 01569 01570 if(interm3Dcell.x < 0 || interm3Dcell.x >= EnvNAVXYTHETACARTLATCfg.EnvWidth_c || 01571 interm3Dcell.y < 0 || interm3Dcell.y >= EnvNAVXYTHETACARTLATCfg.EnvHeight_c) 01572 { 01573 return INFINITECOST; 01574 } 01575 01576 maxcellcost = __max(maxcellcost, EnvNAVXYTHETACARTLATCfg.Grid2D[interm3Dcell.x][interm3Dcell.y]); 01577 01578 //check that the robot is NOT in the cell at which there is no valid orientation 01579 if(maxcellcost >= EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh) 01580 { 01581 return INFINITECOST; 01582 } 01583 } 01584 01585 01586 //check collisions that for the particular footprint orientation along the action 01587 if(EnvNAVXYTHETACARTLATCfg.FootprintPolygon.size() > 1 && (int)maxcellcost >= EnvNAVXYTHETACARTLATCfg.cost_possibly_circumscribed_thresh) 01588 { 01589 checks_cart++; 01590 01591 for(i = 0; i < (int)action->intersectingcellsV.size(); i++) 01592 { 01593 //get the cell in the map 01594 cell = action->intersectingcellsV.at(i); 01595 cell.x = cell.x + SourceX; 01596 cell.y = cell.y + SourceY; 01597 01598 //check validity 01599 if(!IsValidCell(cell.x, cell.y)) 01600 { 01601 return INFINITECOST; 01602 } 01603 01604 //if(EnvNAVXYTHETACARTLATCfg.Grid2D[cell.x][cell.y] > currentmaxcost) //cost computation changed: cost = max(cost of centers of the robot along action) 01605 // currentmaxcost = EnvNAVXYTHETACARTLATCfg.Grid2D[cell.x][cell.y]; //intersecting cells are only used for collision checking 01606 } 01607 } 01608 01609 //to ensure consistency of h2D: 01610 maxcellcost = __max(maxcellcost, EnvNAVXYTHETACARTLATCfg.Grid2D[SourceX][SourceY]); 01611 int currentmaxcost = (int)__max(maxcellcost, EnvNAVXYTHETACARTLATCfg.Grid2D[SourceX + action->dX][SourceY + action->dY]); 01612 01613 01614 return action->cost*(currentmaxcost+1); //use cell cost as multiplicative factor 01615 01616 } 01617 01618 01619 01620 double EnvironmentNAVXYTHETACARTLATTICE::EuclideanDistance_m(int X1, int Y1, int X2, int Y2) 01621 { 01622 int sqdist = ((X1-X2)*(X1-X2)+(Y1-Y2)*(Y1-Y2)); 01623 return EnvNAVXYTHETACARTLATCfg.cellsize_m*sqrt((double)sqdist); 01624 01625 } 01626 01627 01628 //adds points to it (does not clear it beforehand) 01629 void EnvironmentNAVXYTHETACARTLATTICE::CalculateFootprintForPose(EnvNAVXYTHETACARTLAT3Dpt_t pose, vector<sbpl_2Dcell_t>* footprint) 01630 { 01631 int pind; 01632 01633 #if DEBUG 01634 // printf("---Calculating Footprint for Pose: %f %f %f---", 01635 // pose.x, pose.y, pose.theta); 01636 #endif 01637 01638 //handle special case where footprint is just a point 01639 if(EnvNAVXYTHETACARTLATCfg.FootprintPolygon.size() <= 1) 01640 { 01641 sbpl_2Dcell_t cell; 01642 cell.x = CONTXY2DISC(pose.x, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01643 cell.y = CONTXY2DISC(pose.y, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01644 01645 for(pind = 0; pind < (int)footprint->size(); pind++) 01646 { 01647 if(cell.x == footprint->at(pind).x && cell.y == footprint->at(pind).y) 01648 break; 01649 } 01650 if(pind == (int)footprint->size()) footprint->push_back(cell); 01651 return; 01652 } 01653 01654 vector<sbpl_2Dpt_t> bounding_polygon; 01655 unsigned int find; 01656 double max_x = -INFINITECOST, min_x = INFINITECOST, max_y = -INFINITECOST, min_y = INFINITECOST; 01657 sbpl_2Dpt_t pt = {0,0}; 01658 for(find = 0; find < EnvNAVXYTHETACARTLATCfg.FootprintPolygon.size(); find++){ 01659 01660 //rotate and translate the corner of the robot 01661 pt = EnvNAVXYTHETACARTLATCfg.FootprintPolygon[find]; 01662 01663 //rotate and translate the point 01664 sbpl_2Dpt_t corner; 01665 corner.x = cos(pose.theta)*pt.x - sin(pose.theta)*pt.y + pose.x; 01666 corner.y = sin(pose.theta)*pt.x + cos(pose.theta)*pt.y + pose.y; 01667 bounding_polygon.push_back(corner); 01668 #if DEBUG 01669 // printf("Pt: %f %f, Corner: %f %f", pt.x, pt.y, corner.x, corner.y); 01670 #endif 01671 if(corner.x < min_x || find==0){ 01672 min_x = corner.x; 01673 } 01674 if(corner.x > max_x || find==0){ 01675 max_x = corner.x; 01676 } 01677 if(corner.y < min_y || find==0){ 01678 min_y = corner.y; 01679 } 01680 if(corner.y > max_y || find==0){ 01681 max_y = corner.y; 01682 } 01683 01684 } 01685 01686 #if DEBUG 01687 // printf("Footprint bounding box: %f %f %f %f", min_x, max_x, min_y, max_y); 01688 #endif 01689 //initialize previous values to something that will fail the if condition during the first iteration in the for loop 01690 int prev_discrete_x = CONTXY2DISC(pt.x, EnvNAVXYTHETACARTLATCfg.cellsize_m) + 1; 01691 int prev_discrete_y = CONTXY2DISC(pt.y, EnvNAVXYTHETACARTLATCfg.cellsize_m) + 1; 01692 int prev_inside = 0; 01693 int discrete_x; 01694 int discrete_y; 01695 01696 for(double x=min_x; x<=max_x; x+=EnvNAVXYTHETACARTLATCfg.cellsize_m/3){ 01697 for(double y=min_y; y<=max_y; y+=EnvNAVXYTHETACARTLATCfg.cellsize_m/3){ 01698 pt.x = x; 01699 pt.y = y; 01700 discrete_x = CONTXY2DISC(pt.x, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01701 discrete_y = CONTXY2DISC(pt.y, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01702 01703 //see if we just tested this point 01704 if(discrete_x != prev_discrete_x || discrete_y != prev_discrete_y || prev_inside==0){ 01705 01706 #if DEBUG 01707 // printf("Testing point: %f %f Discrete: %d %d", pt.x, pt.y, discrete_x, discrete_y); 01708 #endif 01709 01710 if(IsInsideFootprint(pt, &bounding_polygon)){ 01711 //convert to a grid point 01712 01713 #if DEBUG 01714 // printf("Pt Inside %f %f", pt.x, pt.y); 01715 #endif 01716 01717 sbpl_2Dcell_t cell; 01718 cell.x = discrete_x; 01719 cell.y = discrete_y; 01720 01721 //insert point if not there already 01722 int pind = 0; 01723 for(pind = 0; pind < (int)footprint->size(); pind++) 01724 { 01725 if(cell.x == footprint->at(pind).x && cell.y == footprint->at(pind).y) 01726 break; 01727 } 01728 if(pind == (int)footprint->size()) footprint->push_back(cell); 01729 01730 prev_inside = 1; 01731 01732 #if DEBUG 01733 // printf("Added pt to footprint: %f %f", pt.x, pt.y); 01734 #endif 01735 } 01736 else{ 01737 prev_inside = 0; 01738 } 01739 01740 } 01741 else 01742 { 01743 #if DEBUG 01744 //printf("Skipping pt: %f %f", pt.x, pt.y); 01745 #endif 01746 } 01747 01748 prev_discrete_x = discrete_x; 01749 prev_discrete_y = discrete_y; 01750 01751 }//over x_min...x_max 01752 } 01753 01754 01756 // Do the same for the cart 01758 vector<sbpl_2Dpt_t> bounding_polygon_cart; 01759 unsigned int find_cart; 01760 double max_x_cart = -INFINITECOST, min_x_cart = INFINITECOST, max_y_cart = -INFINITECOST, min_y_cart = INFINITECOST; 01761 sbpl_2Dpt_t pt_cart = {0,0}; 01762 sbpl_2Dpt_t cart_offset_pt; 01763 cart_offset_pt.x = cos(pose.theta)*EnvNAVXYTHETACARTLATCfg.CartOffset.x - sin(pose.theta)*EnvNAVXYTHETACARTLATCfg.CartOffset.y + pose.x; 01764 cart_offset_pt.y = sin(pose.theta)*EnvNAVXYTHETACARTLATCfg.CartOffset.x + cos(pose.theta)*EnvNAVXYTHETACARTLATCfg.CartOffset.y + pose.y; 01765 double cart_angle_global = pose.theta + pose.cartangle; 01766 for(find_cart = 0; find_cart < EnvNAVXYTHETACARTLATCfg.CartPolygon.size(); find_cart++){ 01767 01768 //rotate and translate the corner of the robot 01769 pt_cart = EnvNAVXYTHETACARTLATCfg.CartPolygon[find_cart]; 01770 01771 //rotate and translate the point 01772 sbpl_2Dpt_t corner_cart; 01773 corner_cart.x = cos(cart_angle_global)*pt_cart.x - sin(cart_angle_global)*pt_cart.y + cart_offset_pt.x; 01774 corner_cart.y = sin(cart_angle_global)*pt_cart.x + cos(cart_angle_global)*pt_cart.y + cart_offset_pt.y; 01775 bounding_polygon_cart.push_back(corner_cart); 01776 #if DEBUG 01777 // printf("Pt: %f %f, Corner: %f %f", pt.x, pt.y, corner.x, corner.y); 01778 #endif 01779 if(corner_cart.x < min_x_cart || find_cart==0){ 01780 min_x_cart = corner_cart.x; 01781 } 01782 if(corner_cart.x > max_x_cart || find_cart==0){ 01783 max_x_cart = corner_cart.x; 01784 } 01785 if(corner_cart.y < min_y_cart || find_cart==0){ 01786 min_y_cart = corner_cart.y; 01787 } 01788 if(corner_cart.y > max_y_cart || find_cart==0){ 01789 max_y_cart = corner_cart.y; 01790 } 01791 01792 } 01793 01794 #if DEBUG 01795 // printf("Footprint bounding box: %f %f %f %f", min_x, max_x, min_y, max_y); 01796 #endif 01797 //initialize previous values to something that will fail the if condition during the first iteration in the for loop 01798 int prev_discrete_x_cart = CONTXY2DISC(pt_cart.x, EnvNAVXYTHETACARTLATCfg.cellsize_m) + 1; 01799 int prev_discrete_y_cart = CONTXY2DISC(pt_cart.y, EnvNAVXYTHETACARTLATCfg.cellsize_m) + 1; 01800 int prev_inside_cart = 0; 01801 int discrete_x_cart; 01802 int discrete_y_cart; 01803 01804 for(double x_c=min_x_cart; x_c<=max_x_cart; x_c+=EnvNAVXYTHETACARTLATCfg.cellsize_m/3){ 01805 for(double y_c=min_y_cart; y_c<=max_y_cart; y_c+=EnvNAVXYTHETACARTLATCfg.cellsize_m/3){ 01806 pt_cart.x = x_c; 01807 pt_cart.y = y_c; 01808 discrete_x_cart = CONTXY2DISC(pt_cart.x, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01809 discrete_y_cart = CONTXY2DISC(pt_cart.y, EnvNAVXYTHETACARTLATCfg.cellsize_m); 01810 01811 //see if we just tested this point 01812 if(discrete_x_cart != prev_discrete_x_cart || discrete_y_cart != prev_discrete_y_cart || prev_inside_cart==0){ 01813 01814 #if DEBUG 01815 // printf("Testing point: %f %f Discrete: %d %d", pt.x, pt.y, discrete_x, discrete_y); 01816 #endif 01817 01818 if(IsInsideFootprint(pt_cart, &bounding_polygon_cart)){ 01819 //convert to a grid point 01820 01821 #if DEBUG 01822 // printf("Pt Inside %f %f", pt.x, pt.y); 01823 #endif 01824 01825 sbpl_2Dcell_t cell_cart; 01826 cell_cart.x = discrete_x_cart; 01827 cell_cart.y = discrete_y_cart; 01828 01829 //insert point if not there already 01830 int pind_c = 0; 01831 for(pind_c = 0; pind_c < (int)footprint->size(); pind_c++) 01832 { 01833 if(cell_cart.x == footprint->at(pind_c).x && cell_cart.y == footprint->at(pind_c).y) 01834 break; 01835 } 01836 if(pind_c == (int)footprint->size()) footprint->push_back(cell_cart); 01837 01838 prev_inside_cart = 1; 01839 01840 #if DEBUG 01841 // printf("Added pt to footprint: %f %f", pt.x, pt.y); 01842 #endif 01843 } 01844 else{ 01845 prev_inside_cart = 0; 01846 } 01847 01848 } 01849 else 01850 { 01851 #if DEBUG 01852 //printf("Skipping pt: %f %f", pt.x, pt.y); 01853 #endif 01854 } 01855 01856 prev_discrete_x_cart = discrete_x_cart; 01857 prev_discrete_y_cart = discrete_y_cart; 01858 01859 }//over x_min...x_max 01860 } 01861 } 01862 01863 EnvNAVXYTHETACARTLAT3Dpt_t EnvironmentNAVXYTHETACARTLATTICE::getCartCenter(EnvNAVXYTHETACARTLAT3Dpt_t pose, sbpl_2Dpt_t cart_center_offset) 01864 { 01865 EnvNAVXYTHETACARTLAT3Dpt_t cart_offset_pt; 01866 cart_offset_pt.x = cos(pose.theta)*EnvNAVXYTHETACARTLATCfg.CartOffset.x - sin(pose.theta)*EnvNAVXYTHETACARTLATCfg.CartOffset.y + pose.x; 01867 cart_offset_pt.y = sin(pose.theta)*EnvNAVXYTHETACARTLATCfg.CartOffset.x + cos(pose.theta)*EnvNAVXYTHETACARTLATCfg.CartOffset.y + pose.y; 01868 cart_offset_pt.theta = pose.theta + pose.cartangle; 01869 01870 EnvNAVXYTHETACARTLAT3Dpt_t corner_cart; 01871 corner_cart.x = cos(cart_offset_pt.theta)*cart_center_offset.x - sin(cart_offset_pt.theta)*cart_center_offset.y + cart_offset_pt.x; 01872 corner_cart.y = sin(cart_offset_pt.theta)*cart_center_offset.x + cos(cart_offset_pt.theta)*cart_center_offset.y + cart_offset_pt.y; 01873 corner_cart.theta = cart_offset_pt.theta; 01874 corner_cart.cartangle = pose.cartangle; 01875 return corner_cart; 01876 } 01877 01878 void EnvironmentNAVXYTHETACARTLATTICE::RemoveSourceFootprint(EnvNAVXYTHETACARTLAT3Dpt_t sourcepose, vector<sbpl_2Dcell_t>* footprint) 01879 { 01880 vector<sbpl_2Dcell_t> sourcefootprint; 01881 01882 //compute source footprint 01883 CalculateFootprintForPose(sourcepose, &sourcefootprint); 01884 01885 //now remove the source cells from the footprint 01886 for(int sind = 0; sind < (int)sourcefootprint.size(); sind++) 01887 { 01888 for(int find = 0; find < (int)footprint->size(); find++) 01889 { 01890 if(sourcefootprint.at(sind).x == footprint->at(find).x && sourcefootprint.at(sind).y == footprint->at(find).y) 01891 { 01892 footprint->erase(footprint->begin() + find); 01893 break; 01894 } 01895 }//over footprint 01896 }//over source 01897 } 01898 01899 01900 //------------------------------------------------------------------------------ 01901 01902 //------------------------------Heuristic computation-------------------------- 01903 01904 01905 void EnvironmentNAVXYTHETACARTLATTICE::EnsureHeuristicsUpdated(bool bGoalHeuristics) 01906 { 01907 01908 if(bNeedtoRecomputeStartHeuristics && !bGoalHeuristics) 01909 { 01910 grid2Dsearchfromstart->search(EnvNAVXYTHETACARTLATCfg.Grid2D, EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh, 01911 EnvNAVXYTHETACARTLATCfg.StartX_c, EnvNAVXYTHETACARTLATCfg.StartY_c, EnvNAVXYTHETACARTLATCfg.EndX_c, EnvNAVXYTHETACARTLATCfg.EndY_c, 01912 SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH); 01913 bNeedtoRecomputeStartHeuristics = false; 01914 ROS_DEBUG("2dsolcost_infullunits=%d", (int)(grid2Dsearchfromstart->getlowerboundoncostfromstart_inmm(EnvNAVXYTHETACARTLATCfg.EndX_c, EnvNAVXYTHETACARTLATCfg.EndY_c) 01915 /EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs)); 01916 01917 } 01918 01919 01920 if(bNeedtoRecomputeGoalHeuristics && bGoalHeuristics) 01921 { 01922 grid2Dsearchfromgoal->search(EnvNAVXYTHETACARTLATCfg.Grid2D, EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh, 01923 EnvNAVXYTHETACARTLATCfg.EndX_c, EnvNAVXYTHETACARTLATCfg.EndY_c, EnvNAVXYTHETACARTLATCfg.StartX_c, EnvNAVXYTHETACARTLATCfg.StartY_c, 01924 SBPL_2DGRIDSEARCH_TERM_CONDITION_TWOTIMESOPTPATH); 01925 bNeedtoRecomputeGoalHeuristics = false; 01926 ROS_DEBUG("2dsolcost_infullunits=%d", (int)(grid2Dsearchfromgoal->getlowerboundoncostfromstart_inmm(EnvNAVXYTHETACARTLATCfg.StartX_c, EnvNAVXYTHETACARTLATCfg.StartY_c) 01927 /EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs)); 01928 01929 } 01930 01931 01932 } 01933 01934 01935 01936 void EnvironmentNAVXYTHETACARTLATTICE::ComputeHeuristicValues() 01937 { 01938 //whatever necessary pre-computation of heuristic values is done here 01939 ROS_DEBUG("Precomputing heuristics..."); 01940 01941 //allocated 2D grid searches 01942 grid2Dsearchfromstart = new SBPL2DGridSearch(EnvNAVXYTHETACARTLATCfg.EnvWidth_c, EnvNAVXYTHETACARTLATCfg.EnvHeight_c, (float)EnvNAVXYTHETACARTLATCfg.cellsize_m); 01943 grid2Dsearchfromgoal = new SBPL2DGridSearch(EnvNAVXYTHETACARTLATCfg.EnvWidth_c, EnvNAVXYTHETACARTLATCfg.EnvHeight_c, (float)EnvNAVXYTHETACARTLATCfg.cellsize_m); 01944 01945 //set OPEN type to sliding buckets 01946 grid2Dsearchfromstart->setOPENdatastructure(SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS); 01947 grid2Dsearchfromgoal->setOPENdatastructure(SBPL_2DGRIDSEARCH_OPENTYPE_SLIDINGBUCKETS); 01948 01949 ROS_DEBUG("done"); 01950 01951 } 01952 01953 //------------debugging functions--------------------------------------------- 01954 bool EnvironmentNAVXYTHETACARTLATTICE::CheckQuant(FILE* fOut) 01955 { 01956 01957 for(double theta = -10; theta < 10; theta += 2.0*PI_CONST/NAVXYTHETACARTLAT_THETADIRS*0.01) 01958 { 01959 int nTheta = ContTheta2Disc(theta, NAVXYTHETACARTLAT_THETADIRS); 01960 double newTheta = DiscTheta2Cont(nTheta, NAVXYTHETACARTLAT_THETADIRS); 01961 int nnewTheta = ContTheta2Disc(newTheta, NAVXYTHETACARTLAT_THETADIRS); 01962 01963 SBPL_FPRINTF(fOut, "theta=%f(%f)->%d->%f->%d", theta, theta*180/PI_CONST, nTheta, newTheta, nnewTheta); 01964 01965 if(nTheta != nnewTheta) 01966 { 01967 ROS_ERROR("invalid quantization"); 01968 return false; 01969 } 01970 } 01971 01972 return true; 01973 } 01974 01975 01976 01977 //----------------------------------------------------------------------------- 01978 01979 //-----------interface with outside functions----------------------------------- 01980 bool EnvironmentNAVXYTHETACARTLATTICE::InitializeEnv(const char* sEnvFile, const vector<sbpl_2Dpt_t>& perimeterptsV, const vector<sbpl_2Dpt_t>& cartperimeterptsV, sbpl_2Dpt_t& cart_offset, const char* sMotPrimFile) 01981 { 01982 EnvNAVXYTHETACARTLATCfg.FootprintPolygon = perimeterptsV; 01983 EnvNAVXYTHETACARTLATCfg.CartPolygon = cartperimeterptsV; 01984 EnvNAVXYTHETACARTLATCfg.CartOffset = cart_offset; 01985 01986 FILE* fCfg = fopen(sEnvFile, "r"); 01987 if(fCfg == NULL) 01988 { 01989 ROS_ERROR("unable to open %s", sEnvFile); 01990 initialized_ = false; 01991 return false; 01992 } 01993 ReadConfiguration(fCfg); 01994 01995 if(sMotPrimFile != NULL) 01996 { 01997 FILE* fMotPrim = fopen(sMotPrimFile, "r"); 01998 if(fMotPrim == NULL) 01999 { 02000 ROS_ERROR("unable to open %s", sMotPrimFile); 02001 initialized_ = false; 02002 return false; 02003 } 02004 if(ReadMotionPrimitives(fMotPrim) == false) 02005 { 02006 ROS_ERROR("failed to read in motion primitive file"); 02007 initialized_ = false; 02008 return false; 02009 } 02010 InitGeneral(&EnvNAVXYTHETACARTLATCfg.mprimV); 02011 } 02012 else 02013 InitGeneral(NULL); 02014 02015 ROS_DEBUG("size of env: %d by %d", EnvNAVXYTHETACARTLATCfg.EnvWidth_c, EnvNAVXYTHETACARTLATCfg.EnvHeight_c); 02016 02017 return true; 02018 } 02019 02020 02021 bool EnvironmentNAVXYTHETACARTLATTICE::InitializeEnv(const char* sEnvFile) 02022 { 02023 02024 FILE* fCfg = fopen(sEnvFile, "r"); 02025 if(fCfg == NULL) 02026 { 02027 ROS_ERROR("unable to open %s", sEnvFile); 02028 initialized_ = false; 02029 return false; 02030 } 02031 ReadConfiguration(fCfg); 02032 02033 InitGeneral(NULL); 02034 02035 02036 return true; 02037 } 02038 02039 02040 02041 bool EnvironmentNAVXYTHETACARTLATTICE::InitializeEnv(int width, int height, 02042 const unsigned char* mapdata, 02043 double startx, double starty, double starttheta, double startcartangle, 02044 double goalx, double goaly, double goaltheta, double goalcartangle, 02045 double goaltol_x, double goaltol_y, double goaltol_theta, double goaltol_cartangle, 02046 const vector<sbpl_2Dpt_t> & perimeterptsV, 02047 const sbpl_2Dpt_t & cart_offset, 02048 const vector<sbpl_2Dpt_t> & cart_perimeterptsV, 02049 double cellsize_m, double nominalvel_mpersecs, double timetoturn45degsinplace_secs, 02050 unsigned char obsthresh, const char* sMotPrimFile) 02051 { 02052 ROS_INFO("env: initialize with width=%d height=%d start=%.3f %.3f %.3f goalx=%.3f %.3f %.3f cellsize=%.3f nomvel=%.3f timetoturn=%.3f, obsthresh=%d", 02053 width, height, startx, starty, starttheta, goalx, goaly, goaltheta, cellsize_m, nominalvel_mpersecs, timetoturn45degsinplace_secs, obsthresh); 02054 02055 ROS_INFO("perimeter has size=%zu", perimeterptsV.size()); 02056 02057 for(int i = 0; i < (int)perimeterptsV.size(); i++) 02058 { 02059 ROS_DEBUG("perimeter(%d) = %.4f %.4f", i, perimeterptsV.at(i).x, perimeterptsV.at(i).y); 02060 } 02061 02062 02063 EnvNAVXYTHETACARTLATCfg.obsthresh = obsthresh; 02064 02065 //TODO - need to set the tolerance as well 02066 02067 SetConfiguration(width, 02068 height, 02069 mapdata, 02070 CONTXY2DISC(startx, cellsize_m), 02071 CONTXY2DISC(starty, cellsize_m), 02072 ContTheta2Disc(starttheta, NAVXYTHETACARTLAT_THETADIRS), 02073 ContTheta2Disc(startcartangle, CART_THETADIRS), 02074 CONTXY2DISC(goalx, cellsize_m), 02075 CONTXY2DISC(goaly, cellsize_m), 02076 ContTheta2Disc(goaltheta, NAVXYTHETACARTLAT_THETADIRS), 02077 ContTheta2Disc(goalcartangle, CART_THETADIRS), 02078 cellsize_m, 02079 nominalvel_mpersecs, 02080 timetoturn45degsinplace_secs, 02081 perimeterptsV, 02082 cart_perimeterptsV, 02083 cart_offset); 02084 02085 if(sMotPrimFile != NULL) 02086 { 02087 FILE* fMotPrim = fopen(sMotPrimFile, "r"); 02088 if(fMotPrim == NULL) 02089 { 02090 ROS_ERROR("unable to open %s", sMotPrimFile); 02091 initialized_ = false; 02092 return false; 02093 } 02094 02095 if(ReadMotionPrimitives(fMotPrim) == false) 02096 { 02097 ROS_ERROR("failed to read in motion primitive file"); 02098 initialized_ = false; 02099 return false; 02100 } 02101 } 02102 02103 if(EnvNAVXYTHETACARTLATCfg.mprimV.size() != 0) 02104 { 02105 InitGeneral(&EnvNAVXYTHETACARTLATCfg.mprimV); 02106 } 02107 else 02108 InitGeneral(NULL); 02109 PrintFootprint(); 02110 return true; 02111 } 02112 02113 void EnvironmentNAVXYTHETACARTLATTICE::PrintFootprint() 02114 { 02115 02116 /* 02117 EnvNAVXYTHETACARTLAT3Dpt_t temppose; 02118 FILE *fid = fopen("/tmp/footprint_plot.m","wt"); 02119 ROS_DEBUG ("Print footprint to file"); 02120 for(unsigned int i=0; i < NAVXYTHETACARTLAT_THETADIRS; i++) 02121 { 02122 vector<sbpl_2Dcell_t> footprint; 02123 temppose.x = 0.0 + 3.0*i; 02124 temppose.y = 0.0; 02125 temppose.theta = (i*2*M_PI)/NAVXYTHETACARTLAT_THETADIRS; 02126 temppose.cartangle = 0.0; 02127 CalculateFootprintForPose(temppose, &footprint); 02128 for(int i = 0; i < (int) footprint.size(); i++) 02129 { 02130 fprintf(fid, "%d %d %.3f %.3f", footprint.at(i).x, footprint.at(i).y, 02131 DISCXY2CONT(footprint.at(i).x, EnvNAVXYTHETACARTLATCfg.cellsize_m), 02132 DISCXY2CONT(footprint.at(i).y, EnvNAVXYTHETACARTLATCfg.cellsize_m)); 02133 } 02134 } 02135 fclose(fid);*/ 02136 // printf("number of cells in footprint of the robot = %d", footprint.size()); 02137 // printf("footprint cells (size=%d):", footprint.size()); 02138 02139 /* temppose.x = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02140 temppose.y = DISCXY2CONT(0, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02141 temppose.theta = DiscTheta2Cont(pMotPrim->starttheta_c, NAVXYTHETACARTLAT_THETADIRS); 02142 02143 temppose.x = EnvNAVXYTHETACARTLATCfg.; 02144 temppose.y = 0.0; 02145 temppose.theta = 0.0; 02146 temppose.cartangle = 0.0; 02147 */ 02148 double cart_angle; 02149 for(unsigned int i=0; i < CART_THETADIRS; i++) 02150 { 02151 cart_angle = CartDiscTheta2Cont(i, CART_THETADIRS); 02152 ROS_DEBUG("Cart angle: discretized: %d, actual: %f",i,cart_angle); 02153 } 02154 02155 int cart_angle_d; 02156 for(int i=-10; i <= 10; i++) 02157 { 02158 cart_angle_d = CartContTheta2Disc(i*MAX_CART_ANGLE/10.0, CART_THETADIRS); 02159 ROS_DEBUG("Cart angle: actual: %f, discretized: %d",i*MAX_CART_ANGLE/10.0,cart_angle_d); 02160 } 02161 02162 /* 02163 FILE *fid_env = fopen("/tmp/env.m","wt"); 02164 for (int y = 0; y < EnvNAVXYTHETACARTLATCfg.EnvHeight_c; y++) { 02165 for (int x = 0; x < EnvNAVXYTHETACARTLATCfg.EnvWidth_c; x++) { 02166 fprintf(fid_env,"%d ",EnvNAVXYTHETACARTLATCfg.Grid2D[x][y]); 02167 } 02168 fprintf(fid_env,""); 02169 } 02170 fclose(fid_env); */ 02171 02172 } 02173 02174 02175 bool EnvironmentNAVXYTHETACARTLATTICE::InitGeneral(vector<SBPL_xythetacart_mprimitive>* motionprimitiveV) { 02176 02177 02178 //Initialize other parameters of the environment 02179 InitializeEnvConfig(motionprimitiveV); 02180 02181 //initialize Environment 02182 InitializeEnvironment(); 02183 02184 //pre-compute heuristics 02185 ComputeHeuristicValues(); 02186 02187 return true; 02188 } 02189 02190 bool EnvironmentNAVXYTHETACARTLATTICE::InitializeMDPCfg(MDPConfig *MDPCfg) 02191 { 02192 //initialize MDPCfg with the start and goal ids 02193 MDPCfg->goalstateid = EnvNAVXYTHETACARTLAT.goalstateid; 02194 MDPCfg->startstateid = EnvNAVXYTHETACARTLAT.startstateid; 02195 02196 return true; 02197 } 02198 02199 02200 void EnvironmentNAVXYTHETACARTLATTICE::PrintHeuristicValues() 02201 { 02202 FILE* fHeur = fopen("heur.txt", "w"); 02203 SBPL2DGridSearch* grid2Dsearch = NULL; 02204 02205 for(int i = 0; i < 2; i++) 02206 { 02207 if(i == 0 && grid2Dsearchfromstart != NULL) 02208 { 02209 grid2Dsearch = grid2Dsearchfromstart; 02210 SBPL_FPRINTF(fHeur, "Start heuristics:"); 02211 } 02212 else if(i == 1 && grid2Dsearchfromgoal != NULL) 02213 { 02214 grid2Dsearch = grid2Dsearchfromgoal; 02215 SBPL_FPRINTF(fHeur, "Goal heuristics:"); 02216 } 02217 else 02218 continue; 02219 02220 for (int y = 0; y < EnvNAVXYTHETACARTLATCfg.EnvHeight_c; y++) { 02221 for (int x = 0; x < EnvNAVXYTHETACARTLATCfg.EnvWidth_c; x++) { 02222 if(grid2Dsearch->getlowerboundoncostfromstart_inmm(x, y) < INFINITECOST) 02223 SBPL_FPRINTF(fHeur, "%5d ", grid2Dsearch->getlowerboundoncostfromstart_inmm(x, y)); 02224 else 02225 SBPL_FPRINTF(fHeur, "XXXXX "); 02226 } 02227 SBPL_FPRINTF(fHeur, " "); 02228 } 02229 } 02230 fclose(fHeur); 02231 } 02232 02233 02234 02235 02236 void EnvironmentNAVXYTHETACARTLATTICE::SetAllPreds(CMDPSTATE* state) 02237 { 02238 //implement this if the planner needs access to predecessors 02239 02240 ROS_ERROR("ERROR in EnvNAVXYTHETACARTLAT... function: SetAllPreds is undefined"); 02241 return; 02242 } 02243 02244 02245 void EnvironmentNAVXYTHETACARTLATTICE::GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV) 02246 { 02247 GetSuccs(SourceStateID, SuccIDV, CostV, NULL); 02248 } 02249 02250 02251 02252 02253 02254 const EnvNAVXYTHETACARTLATConfig_t* EnvironmentNAVXYTHETACARTLATTICE::GetEnvNavConfig() { 02255 return &EnvNAVXYTHETACARTLATCfg; 02256 } 02257 02258 02259 02260 bool EnvironmentNAVXYTHETACARTLATTICE::UpdateCost(int x, int y, unsigned char newcost) 02261 { 02262 02263 #if DEBUG 02264 //fprintf(fDeb, "Cost updated for cell %d %d from old cost=%d to new cost=%d", x,y,EnvNAVXYTHETACARTLATCfg.Grid2D[x][y], newcost); 02265 #endif 02266 02267 EnvNAVXYTHETACARTLATCfg.Grid2D[x][y] = newcost; 02268 02269 bNeedtoRecomputeStartHeuristics = true; 02270 bNeedtoRecomputeGoalHeuristics = true; 02271 02272 return true; 02273 } 02274 02275 02276 void EnvironmentNAVXYTHETACARTLATTICE::PrintEnv_Config(FILE* fOut) 02277 { 02278 02279 //implement this if the planner needs to print out EnvNAVXYTHETACARTLAT. configuration 02280 02281 ROS_ERROR("ERROR in EnvNAVXYTHETACARTLAT... function: PrintEnv_Config is undefined"); 02282 return; 02283 } 02284 02285 void EnvironmentNAVXYTHETACARTLATTICE::PrintTimeStat(FILE* fOut) 02286 { 02287 02288 #if TIME_DEBUG 02289 SBPL_FPRINTF(fOut, "time3_addallout = %f secs, time_gethash = %f secs, time_createhash = %f secs, time_getsuccs = %f", 02290 time3_addallout/(double)CLOCKS_PER_SEC, time_gethash/(double)CLOCKS_PER_SEC, 02291 time_createhash/(double)CLOCKS_PER_SEC, time_getsuccs/(double)CLOCKS_PER_SEC); 02292 #endif 02293 } 02294 02295 02296 02297 bool EnvironmentNAVXYTHETACARTLATTICE::IsObstacle(int x, int y) 02298 { 02299 02300 #if DEBUG 02301 SBPL_FPRINTF(fDeb, "Status of cell %d %d is queried. Its cost=%d", x,y,EnvNAVXYTHETACARTLATCfg.Grid2D[x][y]); 02302 #endif 02303 02304 02305 return (EnvNAVXYTHETACARTLATCfg.Grid2D[x][y] >= EnvNAVXYTHETACARTLATCfg.obsthresh); 02306 02307 } 02308 02309 // NOT USED 02310 void EnvironmentNAVXYTHETACARTLATTICE::GetEnvParms(int *size_x, int *size_y, 02311 double* startx, double* starty, double*starttheta, double*startcartangle, 02312 double* goalx, double* goaly, double* goaltheta, double*goalcartangle, 02313 double* cellsize_m, double* nominalvel_mpersecs, 02314 double* timetoturn45degsinplace_secs, unsigned char* obsthresh, 02315 vector<SBPL_xythetacart_mprimitive>* mprimitiveV) 02316 { 02317 *size_x = EnvNAVXYTHETACARTLATCfg.EnvWidth_c; 02318 *size_y = EnvNAVXYTHETACARTLATCfg.EnvHeight_c; 02319 02320 *startx = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.StartX_c, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02321 *starty = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.StartY_c, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02322 *starttheta = DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.StartTheta, NAVXYTHETACARTLAT_THETADIRS); 02323 *startcartangle = CartDiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.StartCartAngle, CART_THETADIRS); 02324 02325 *goalx = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.EndX_c, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02326 *goaly = DISCXY2CONT(EnvNAVXYTHETACARTLATCfg.EndY_c, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02327 *goaltheta = DiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.EndTheta, NAVXYTHETACARTLAT_THETADIRS); 02328 *goalcartangle = CartDiscTheta2Cont(EnvNAVXYTHETACARTLATCfg.EndCartAngle, CART_THETADIRS); 02329 02330 *cellsize_m = EnvNAVXYTHETACARTLATCfg.cellsize_m; 02331 *nominalvel_mpersecs = EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs; 02332 *timetoturn45degsinplace_secs = EnvNAVXYTHETACARTLATCfg.timetoturn45degsinplace_secs; 02333 02334 *obsthresh = EnvNAVXYTHETACARTLATCfg.obsthresh; 02335 02336 *mprimitiveV = EnvNAVXYTHETACARTLATCfg.mprimV; 02337 } 02338 02339 unsigned char EnvironmentNAVXYTHETACARTLATTICE::GetMapCost(int x, int y) 02340 { 02341 return EnvNAVXYTHETACARTLATCfg.Grid2D[x][y]; 02342 } 02343 02344 bool EnvironmentNAVXYTHETACARTLATTICE::SetEnvParameter(const char* parameter, int value) 02345 { 02346 02347 if(EnvNAVXYTHETACARTLAT.bInitialized == true) 02348 { 02349 ROS_ERROR("all parameters must be set before initialization of the environment"); 02350 return false; 02351 } 02352 02353 ROS_DEBUG("setting parameter %s to %d", parameter, value); 02354 02355 if(strcmp(parameter, "cost_inscribed_thresh") == 0) 02356 { 02357 if(value < 0 || value > 255) 02358 { 02359 ROS_ERROR("invalid value %d for parameter %s", value, parameter); 02360 return false; 02361 } 02362 EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh = (unsigned char)value; 02363 } 02364 else if(strcmp(parameter, "cost_possibly_circumscribed_thresh") == 0) 02365 { 02366 if(value < 0 || value > 255) 02367 { 02368 ROS_ERROR("invalid value %d for parameter %s", value, parameter); 02369 return false; 02370 } 02371 EnvNAVXYTHETACARTLATCfg.cost_possibly_circumscribed_thresh = value; 02372 } 02373 else if(strcmp(parameter, "cost_obsthresh") == 0) 02374 { 02375 if(value < 0 || value > 255) 02376 { 02377 ROS_ERROR("invalid value %d for parameter %s", value, parameter); 02378 return false; 02379 } 02380 EnvNAVXYTHETACARTLATCfg.obsthresh = (unsigned char)value; 02381 } 02382 else 02383 { 02384 ROS_ERROR("invalid parameter %s", parameter); 02385 return false; 02386 } 02387 02388 return true; 02389 } 02390 02391 int EnvironmentNAVXYTHETACARTLATTICE::GetEnvParameter(const char* parameter) 02392 { 02393 02394 if(strcmp(parameter, "cost_inscribed_thresh") == 0) 02395 { 02396 return (int) EnvNAVXYTHETACARTLATCfg.cost_inscribed_thresh; 02397 } 02398 else if(strcmp(parameter, "cost_possibly_circumscribed_thresh") == 0) 02399 { 02400 return (int) EnvNAVXYTHETACARTLATCfg.cost_possibly_circumscribed_thresh; 02401 } 02402 else if(strcmp(parameter, "cost_obsthresh") == 0) 02403 { 02404 return (int) EnvNAVXYTHETACARTLATCfg.obsthresh; 02405 } 02406 else 02407 { 02408 ROS_ERROR("invalid parameter %s", parameter); 02409 throw new SBPL_Exception(); 02410 } 02411 } 02412 02413 //------------------------------------------------------------------------------ 02414 02415 02416 02417 //-----------------XYTHETA Enivornment (child) class--------------------------- 02418 02419 EnvironmentNAVXYTHETACARTLAT::~EnvironmentNAVXYTHETACARTLAT() 02420 { 02421 ROS_DEBUG("destroying XYTHETACARTLAT"); 02422 02423 //delete the states themselves first 02424 for (int i = 0; i < (int)StateID2CoordTable.size(); i++) 02425 { 02426 delete StateID2CoordTable.at(i); 02427 StateID2CoordTable.at(i) = NULL; 02428 } 02429 StateID2CoordTable.clear(); 02430 02431 //delete hashtable 02432 if(Coord2StateIDHashTable != NULL) 02433 { 02434 delete [] Coord2StateIDHashTable; 02435 Coord2StateIDHashTable = NULL; 02436 } 02437 if(Coord2StateIDHashTable_lookup != NULL) 02438 { 02439 delete [] Coord2StateIDHashTable_lookup; 02440 Coord2StateIDHashTable_lookup = NULL; 02441 } 02442 02443 } 02444 02445 02446 void EnvironmentNAVXYTHETACARTLAT::GetCoordFromState(int stateID, int& x, int& y, int& theta, int &cartangle) const { 02447 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = StateID2CoordTable[stateID]; 02448 x = HashEntry->X; 02449 y = HashEntry->Y; 02450 theta = HashEntry->Theta; 02451 cartangle = HashEntry->CartAngle; 02452 } 02453 02454 int EnvironmentNAVXYTHETACARTLAT::GetStateFromCoord(int x, int y, int theta, int cartangle) { 02455 02456 EnvNAVXYTHETACARTLATHashEntry_t* OutHashEntry; 02457 if((OutHashEntry = (this->*GetHashEntry)(x, y, theta,cartangle)) == NULL){ 02458 //have to create a new entry 02459 OutHashEntry = (this->*CreateNewHashEntry)(x, y, theta,cartangle); 02460 } 02461 return OutHashEntry->stateID; 02462 } 02463 02464 bool EnvironmentNAVXYTHETACARTLAT::ConvertStateIDPathintoXYThetaPath(vector<int>* stateIDPath, vector<EnvNAVXYTHETACARTLAT3Dpt_t>* xythetaPath) 02465 { 02466 vector<EnvNAVXYTHETACARTLATAction_t*> actionV; 02467 vector<int> CostV; 02468 vector<int> SuccIDV; 02469 int targetx_c, targety_c, targettheta_c, targetcartangle_c; 02470 int sourcex_c, sourcey_c, sourcetheta_c, sourcecartangle_c; 02471 02472 ROS_DEBUG("checks_cart=%ld", checks_cart); 02473 02474 xythetaPath->clear(); 02475 02476 #if DEBUG 02477 SBPL_FPRINTF(fDeb, "converting stateid path into coordinates:"); 02478 #endif 02479 02480 for(int pind = 0; pind < (int)(stateIDPath->size())-1; pind++) 02481 { 02482 int sourceID = stateIDPath->at(pind); 02483 int targetID = stateIDPath->at(pind+1); 02484 02485 #if DEBUG 02486 GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcecartangle_c); 02487 #endif 02488 02489 02490 //get successors and pick the target via the cheapest action 02491 SuccIDV.clear(); 02492 CostV.clear(); 02493 actionV.clear(); 02494 GetSuccs(sourceID, &SuccIDV, &CostV, &actionV); 02495 02496 int bestcost = INFINITECOST; 02497 int bestsind = -1; 02498 02499 #if DEBUG 02500 GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcecartangle_c); 02501 GetCoordFromState(targetID, targetx_c, targety_c, targettheta_c, targetcartangle_c); 02502 SBPL_FPRINTF(fDeb, "looking for %d %d %d %d -> %d %d %d %d (numofsuccs=%zu)", sourcex_c, sourcey_c, sourcetheta_c, sourcecartangle_c, 02503 targetx_c, targety_c, targettheta_c, targetcartangle_c, SuccIDV.size()); 02504 02505 #endif 02506 02507 for(int sind = 0; sind < (int)SuccIDV.size(); sind++) 02508 { 02509 02510 #if DEBUG 02511 int x_c, y_c, theta_c, cartangle_c; 02512 GetCoordFromState(SuccIDV[sind], x_c, y_c, theta_c, cartangle_c); 02513 SBPL_FPRINTF(fDeb, "succ: %d %d %d %d", x_c, y_c, theta_c, cartangle_c); 02514 #endif 02515 02516 if(SuccIDV[sind] == targetID && CostV[sind] <= bestcost) 02517 { 02518 bestcost = CostV[sind]; 02519 bestsind = sind; 02520 } 02521 } 02522 if(bestsind == -1) 02523 { 02524 ROS_ERROR("successor not found for transition:"); 02525 GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcecartangle_c); 02526 GetCoordFromState(targetID, targetx_c, targety_c, targettheta_c, targetcartangle_c); 02527 ROS_ERROR("%d %d %d %d -> %d %d %d %d", sourcex_c, sourcey_c, sourcetheta_c, sourcecartangle_c, 02528 targetx_c, targety_c, targettheta_c, targetcartangle_c); 02529 return false; 02530 } 02531 02532 //now push in the actual path 02533 int sourcex_c, sourcey_c, sourcetheta_c, sourcecartangle_c; 02534 GetCoordFromState(sourceID, sourcex_c, sourcey_c, sourcetheta_c, sourcecartangle_c); 02535 double sourcex, sourcey; 02536 sourcex = DISCXY2CONT(sourcex_c, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02537 sourcey = DISCXY2CONT(sourcey_c, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02538 //TODO - when there are no motion primitives we should still print source state 02539 for(int ipind = 0; ipind < ((int)actionV[bestsind]->intermptV.size())-1; ipind++) 02540 { 02541 //translate appropriately 02542 EnvNAVXYTHETACARTLAT3Dpt_t intermpt = actionV[bestsind]->intermptV[ipind]; 02543 intermpt.x += sourcex; 02544 intermpt.y += sourcey; 02545 02546 #if DEBUG 02547 int nx = CONTXY2DISC(intermpt.x, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02548 int ny = CONTXY2DISC(intermpt.y, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02549 SBPL_FPRINTF(fDeb, "%.3f %.3f %.3f (%d %d %d cost=%d) ", 02550 intermpt.x, intermpt.y, intermpt.theta, 02551 nx, ny, 02552 ContTheta2Disc(intermpt.theta, NAVXYTHETACARTLAT_THETADIRS), EnvNAVXYTHETACARTLATCfg.Grid2D[nx][ny]); 02553 if(ipind == 0) SBPL_FPRINTF(fDeb, "first (heur=%d)", GetStartHeuristic(sourceID)); 02554 else SBPL_FPRINTF(fDeb, ""); 02555 #endif 02556 02557 //store 02558 xythetaPath->push_back(intermpt); 02559 } 02560 } 02561 return true; 02562 } 02563 02564 02565 //returns the stateid if success, and -1 otherwise 02566 int EnvironmentNAVXYTHETACARTLAT::SetGoal(double x_m, double y_m, double theta_rad, double cartangle_rad){ 02567 02568 int x = CONTXY2DISC(x_m, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02569 int y = CONTXY2DISC(y_m, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02570 int theta = ContTheta2Disc(theta_rad, NAVXYTHETACARTLAT_THETADIRS); 02571 int cartangle = CartContTheta2Disc(cartangle_rad, CART_THETADIRS); 02572 02573 ROS_DEBUG("Env: setting goal to %.3f %.3f %.3f %.3f (%d %d %d %d)", x_m, y_m, theta_rad, cartangle_rad, x, y, theta, cartangle); 02574 02575 if(!IsWithinMapCell(x,y)) 02576 { 02577 ROS_ERROR("Trying to set a goal cell %d %d that is outside of map", x,y); 02578 return -1; 02579 } 02580 02581 if(!IsValidConfiguration(x,y,theta,cartangle)) 02582 { 02583 ROS_WARN("Goal configuration is invalid"); 02584 } 02585 02586 EnvNAVXYTHETACARTLATHashEntry_t* OutHashEntry; 02587 if((OutHashEntry = (this->*GetHashEntry)(x, y, theta, cartangle)) == NULL){ 02588 //have to create a new entry 02589 OutHashEntry = (this->*CreateNewHashEntry)(x, y, theta, cartangle); 02590 } 02591 02592 //need to recompute start heuristics? 02593 if(EnvNAVXYTHETACARTLAT.goalstateid != OutHashEntry->stateID) 02594 { 02595 bNeedtoRecomputeStartHeuristics = true; //because termination condition may not plan all the way to the new goal 02596 bNeedtoRecomputeGoalHeuristics = true; //because goal heuristics change 02597 } 02598 02599 02600 02601 EnvNAVXYTHETACARTLAT.goalstateid = OutHashEntry->stateID; 02602 02603 EnvNAVXYTHETACARTLATCfg.EndX_c = x; 02604 EnvNAVXYTHETACARTLATCfg.EndY_c = y; 02605 EnvNAVXYTHETACARTLATCfg.EndTheta = theta; 02606 EnvNAVXYTHETACARTLATCfg.EndCartAngle = cartangle; 02607 02608 PrintFootprint(); 02609 return EnvNAVXYTHETACARTLAT.goalstateid; 02610 02611 } 02612 02613 02614 //returns the stateid if success, and -1 otherwise 02615 int EnvironmentNAVXYTHETACARTLAT::SetStart(double x_m, double y_m, double theta_rad, double cartangle_rad){ 02616 02617 int x = CONTXY2DISC(x_m, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02618 int y = CONTXY2DISC(y_m, EnvNAVXYTHETACARTLATCfg.cellsize_m); 02619 int theta = ContTheta2Disc(theta_rad, NAVXYTHETACARTLAT_THETADIRS); 02620 int cartangle = CartContTheta2Disc(cartangle_rad, CART_THETADIRS); 02621 02622 if(!IsWithinMapCell(x,y)) 02623 { 02624 ROS_ERROR("trying to set a start cell %d %d that is outside of map", x,y); 02625 return -1; 02626 } 02627 02628 ROS_DEBUG("Env: setting start to %.3f %.3f %.3f %.3f (%d %d %d %d)", x_m, y_m, theta_rad, cartangle_rad, x, y, theta, cartangle); 02629 02630 if(!IsValidConfiguration(x,y,theta,cartangle)) 02631 { 02632 ROS_WARN("start configuration %d %d %d %d is invalid", x,y,theta,cartangle); 02633 } 02634 02635 EnvNAVXYTHETACARTLATHashEntry_t* OutHashEntry; 02636 if((OutHashEntry = (this->*GetHashEntry)(x, y, theta, cartangle)) == NULL){ 02637 //have to create a new entry 02638 OutHashEntry = (this->*CreateNewHashEntry)(x, y, theta, cartangle); 02639 } 02640 02641 //need to recompute start heuristics? 02642 if(EnvNAVXYTHETACARTLAT.startstateid != OutHashEntry->stateID) 02643 { 02644 bNeedtoRecomputeStartHeuristics = true; 02645 bNeedtoRecomputeGoalHeuristics = true; //because termination condition can be not all states TODO - make it dependent on term. condition 02646 } 02647 02648 //set start 02649 EnvNAVXYTHETACARTLAT.startstateid = OutHashEntry->stateID; 02650 EnvNAVXYTHETACARTLATCfg.StartX_c = x; 02651 EnvNAVXYTHETACARTLATCfg.StartY_c = y; 02652 EnvNAVXYTHETACARTLATCfg.StartTheta = theta; 02653 EnvNAVXYTHETACARTLATCfg.StartCartAngle = cartangle; 02654 02655 return EnvNAVXYTHETACARTLAT.startstateid; 02656 02657 } 02658 02659 void EnvironmentNAVXYTHETACARTLAT::PrintState(int stateID, bool bVerbose, FILE* fOut /*=NULL*/) 02660 { 02661 #if DEBUG 02662 if(stateID >= (int)StateID2CoordTable.size()) 02663 { 02664 ROS_ERROR("ERROR in EnvNAVXYTHETACARTLAT... function: stateID illegal (2)"); 02665 } 02666 #endif 02667 02668 if(fOut == NULL) 02669 fOut = stdout; 02670 02671 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = StateID2CoordTable[stateID]; 02672 02673 if(stateID == EnvNAVXYTHETACARTLAT.goalstateid && bVerbose) 02674 { 02675 SBPL_FPRINTF(fOut, "This state is a goal state:"); 02676 } 02677 02678 if(bVerbose) 02679 SBPL_FPRINTF(fOut, "X=%d Y=%d Theta=%d CartAngle=%d", HashEntry->X, HashEntry->Y, HashEntry->Theta, HashEntry->CartAngle); 02680 else 02681 SBPL_FPRINTF(fOut, "%.3f %.3f %.3f %.3f", DISCXY2CONT(HashEntry->X, EnvNAVXYTHETACARTLATCfg.cellsize_m), DISCXY2CONT(HashEntry->Y,EnvNAVXYTHETACARTLATCfg.cellsize_m), 02682 DiscTheta2Cont(HashEntry->Theta, NAVXYTHETACARTLAT_THETADIRS), CartDiscTheta2Cont(HashEntry->CartAngle, CART_THETADIRS)); 02683 02684 } 02685 02686 02687 EnvNAVXYTHETACARTLATHashEntry_t* EnvironmentNAVXYTHETACARTLAT::GetHashEntry_lookup(int X, int Y, int Theta, int CartAngle) 02688 { 02689 int index = XYTHETACART2INDEX(X,Y,Theta,CartAngle); 02690 return Coord2StateIDHashTable_lookup[index]; 02691 } 02692 02693 02694 EnvNAVXYTHETACARTLATHashEntry_t* EnvironmentNAVXYTHETACARTLAT::GetHashEntry_hash(int X, int Y, int Theta, int CartAngle) 02695 { 02696 02697 #if TIME_DEBUG 02698 clock_t currenttime = clock(); 02699 #endif 02700 02701 int binid = GETHASHBIN(X, Y, Theta, CartAngle); 02702 02703 #if DEBUG 02704 if ((int)Coord2StateIDHashTable[binid].size() > 5) 02705 { 02706 SBPL_FPRINTF(fDeb, "WARNING: Hash table has a bin %d (X=%d Y=%d) of size %zu", 02707 binid, X, Y, Coord2StateIDHashTable[binid].size()); 02708 02709 PrintHashTableHist(fDeb); 02710 } 02711 #endif 02712 02713 //iterate over the states in the bin and select the perfect match 02714 vector<EnvNAVXYTHETACARTLATHashEntry_t*>* binV = &Coord2StateIDHashTable[binid]; 02715 for(int ind = 0; ind < (int)binV->size(); ind++) 02716 { 02717 EnvNAVXYTHETACARTLATHashEntry_t* hashentry = binV->at(ind); 02718 if( hashentry->X == X && hashentry->Y == Y && hashentry->Theta == Theta && hashentry->CartAngle == CartAngle) 02719 { 02720 #if TIME_DEBUG 02721 time_gethash += clock()-currenttime; 02722 #endif 02723 return hashentry; 02724 } 02725 } 02726 02727 #if TIME_DEBUG 02728 time_gethash += clock()-currenttime; 02729 #endif 02730 02731 return NULL; 02732 } 02733 02734 EnvNAVXYTHETACARTLATHashEntry_t* EnvironmentNAVXYTHETACARTLAT::CreateNewHashEntry_lookup(int X, int Y, int Theta, int CartAngle) 02735 { 02736 int i; 02737 02738 #if TIME_DEBUG 02739 clock_t currenttime = clock(); 02740 #endif 02741 02742 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = new EnvNAVXYTHETACARTLATHashEntry_t; 02743 02744 HashEntry->X = X; 02745 HashEntry->Y = Y; 02746 HashEntry->Theta = Theta; 02747 HashEntry->CartAngle = CartAngle; 02748 HashEntry->iteration = 0; 02749 02750 HashEntry->stateID = StateID2CoordTable.size(); 02751 02752 //insert into the tables 02753 StateID2CoordTable.push_back(HashEntry); 02754 02755 int index = XYTHETACART2INDEX(X,Y,Theta,CartAngle); 02756 02757 #if DEBUG 02758 if(Coord2StateIDHashTable_lookup[index] != NULL) 02759 { 02760 ROS_ERROR("creating hash entry for non-NULL hashentry"); 02761 throw new SBPL_Exception(); 02762 } 02763 #endif 02764 02765 Coord2StateIDHashTable_lookup[index] = HashEntry; 02766 02767 //insert into and initialize the mappings 02768 int* entry = new int [NUMOFINDICES_STATEID2IND]; 02769 StateID2IndexMapping.push_back(entry); 02770 for(i = 0; i < NUMOFINDICES_STATEID2IND; i++) 02771 { 02772 StateID2IndexMapping[HashEntry->stateID][i] = -1; 02773 } 02774 02775 if(HashEntry->stateID != (int)StateID2IndexMapping.size()-1) 02776 { 02777 ROS_ERROR("ERROR in Env... function: last state has incorrect stateID"); 02778 throw new SBPL_Exception(); 02779 } 02780 02781 #if TIME_DEBUG 02782 time_createhash += clock()-currenttime; 02783 #endif 02784 02785 return HashEntry; 02786 } 02787 02788 02789 02790 02791 EnvNAVXYTHETACARTLATHashEntry_t* EnvironmentNAVXYTHETACARTLAT::CreateNewHashEntry_hash(int X, int Y, int Theta, int CartAngle) 02792 { 02793 int i; 02794 02795 #if TIME_DEBUG 02796 clock_t currenttime = clock(); 02797 #endif 02798 02799 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = new EnvNAVXYTHETACARTLATHashEntry_t; 02800 02801 HashEntry->X = X; 02802 HashEntry->Y = Y; 02803 HashEntry->Theta = Theta; 02804 HashEntry->CartAngle = CartAngle; 02805 HashEntry->iteration = 0; 02806 02807 HashEntry->stateID = StateID2CoordTable.size(); 02808 02809 //insert into the tables 02810 StateID2CoordTable.push_back(HashEntry); 02811 02812 02813 //get the hash table bin 02814 i = GETHASHBIN(HashEntry->X, HashEntry->Y, HashEntry->Theta, HashEntry->CartAngle); 02815 02816 //insert the entry into the bin 02817 Coord2StateIDHashTable[i].push_back(HashEntry); 02818 02819 //insert into and initialize the mappings 02820 int* entry = new int [NUMOFINDICES_STATEID2IND]; 02821 StateID2IndexMapping.push_back(entry); 02822 for(i = 0; i < NUMOFINDICES_STATEID2IND; i++) 02823 { 02824 StateID2IndexMapping[HashEntry->stateID][i] = -1; 02825 } 02826 02827 if(HashEntry->stateID != (int)StateID2IndexMapping.size()-1) 02828 { 02829 ROS_ERROR("ERROR in Env... function: last state has incorrect stateID"); 02830 delete HashEntry; 02831 return NULL; // TODO 02832 } 02833 02834 #if TIME_DEBUG 02835 time_createhash += clock()-currenttime; 02836 #endif 02837 02838 return HashEntry; 02839 } 02840 02841 02842 02843 void EnvironmentNAVXYTHETACARTLAT::GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV, vector<EnvNAVXYTHETACARTLATAction_t*>* actionV /*=NULL*/) 02844 { 02845 int aind; 02846 02847 #if TIME_DEBUG 02848 clock_t currenttime = clock(); 02849 #endif 02850 02851 //clear the successor array 02852 SuccIDV->clear(); 02853 CostV->clear(); 02854 SuccIDV->reserve(EnvNAVXYTHETACARTLATCfg.actionwidth); 02855 CostV->reserve(EnvNAVXYTHETACARTLATCfg.actionwidth); 02856 if(actionV != NULL) 02857 { 02858 actionV->clear(); 02859 actionV->reserve(EnvNAVXYTHETACARTLATCfg.actionwidth); 02860 } 02861 02862 //goal state should be absorbing 02863 if(SourceStateID == EnvNAVXYTHETACARTLAT.goalstateid) 02864 return; 02865 02866 //get X, Y for the state 02867 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = StateID2CoordTable[SourceStateID]; 02868 02869 //iterate through actions 02870 for (aind = 0; aind < EnvNAVXYTHETACARTLATCfg.actionwidth; aind++) 02871 { 02872 EnvNAVXYTHETACARTLATAction_t* nav3daction = &EnvNAVXYTHETACARTLATCfg.ActionsV[(int)HashEntry->Theta][aind]; 02873 int newX = HashEntry->X + nav3daction->dX; 02874 int newY = HashEntry->Y + nav3daction->dY; 02875 int newTheta = NORMALIZEDISCTHETA(nav3daction->endtheta, NAVXYTHETACARTLAT_THETADIRS); 02876 // TODO 02877 int newCartAngle = nav3daction->endcartangle; 02878 02879 //skip the invalid cells 02880 if(!IsValidCell(newX, newY)) 02881 continue; 02882 02883 //get cost 02884 int cost = GetActionCost(HashEntry->X, HashEntry->Y, HashEntry->Theta, HashEntry->CartAngle, nav3daction); 02885 if(cost >= INFINITECOST) 02886 continue; 02887 02888 EnvNAVXYTHETACARTLATHashEntry_t* OutHashEntry; 02889 if((OutHashEntry = (this->*GetHashEntry)(newX, newY, newTheta, newCartAngle)) == NULL) 02890 { 02891 //have to create a new entry 02892 OutHashEntry = (this->*CreateNewHashEntry)(newX, newY, newTheta, newCartAngle); 02893 } 02894 02895 SuccIDV->push_back(OutHashEntry->stateID); 02896 CostV->push_back(cost); 02897 if(actionV != NULL) 02898 actionV->push_back(nav3daction); 02899 } 02900 02901 #if TIME_DEBUG 02902 time_getsuccs += clock()-currenttime; 02903 #endif 02904 02905 } 02906 02907 void EnvironmentNAVXYTHETACARTLAT::GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* CostV) 02908 { 02909 02910 //TODO- to support tolerance, need: a) generate preds for goal state based on all possible goal state variable settings, 02911 //b) change goal check condition in gethashentry c) change getpredsofchangedcells and getsuccsofchangedcells functions 02912 02913 int aind; 02914 02915 #if TIME_DEBUG 02916 clock_t currenttime = clock(); 02917 #endif 02918 02919 //get X, Y for the state 02920 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = StateID2CoordTable[TargetStateID]; 02921 02922 //clear the successor array 02923 PredIDV->clear(); 02924 CostV->clear(); 02925 PredIDV->reserve(EnvNAVXYTHETACARTLATCfg.PredActionsV[(int)HashEntry->Theta].size()); 02926 CostV->reserve(EnvNAVXYTHETACARTLATCfg.PredActionsV[(int)HashEntry->Theta].size()); 02927 02928 //iterate through actions 02929 vector<EnvNAVXYTHETACARTLATAction_t*>* actionsV = &EnvNAVXYTHETACARTLATCfg.PredActionsV[(int)HashEntry->Theta]; 02930 for (aind = 0; aind < (int)EnvNAVXYTHETACARTLATCfg.PredActionsV[(int)HashEntry->Theta].size(); aind++) 02931 { 02932 02933 EnvNAVXYTHETACARTLATAction_t* nav3daction = actionsV->at(aind); 02934 02935 int predX = HashEntry->X - nav3daction->dX; 02936 int predY = HashEntry->Y - nav3daction->dY; 02937 int predTheta = nav3daction->starttheta; 02938 int predCartAngle = nav3daction->startcartangle; 02939 02940 02941 //skip the invalid cells 02942 if(!IsValidCell(predX, predY)) 02943 continue; 02944 02945 //get cost 02946 int cost = GetActionCost(predX, predY, predTheta, predCartAngle, nav3daction); 02947 if(cost >= INFINITECOST) 02948 continue; 02949 02950 EnvNAVXYTHETACARTLATHashEntry_t* OutHashEntry; 02951 if((OutHashEntry = (this->*GetHashEntry)(predX, predY, predTheta, predCartAngle)) == NULL) 02952 { 02953 //have to create a new entry 02954 OutHashEntry = (this->*CreateNewHashEntry)(predX, predY, predTheta, predCartAngle); 02955 } 02956 02957 PredIDV->push_back(OutHashEntry->stateID); 02958 CostV->push_back(cost); 02959 } 02960 02961 #if TIME_DEBUG 02962 time_getsuccs += clock()-currenttime; 02963 #endif 02964 } 02965 02966 void EnvironmentNAVXYTHETACARTLAT::SetAllActionsandAllOutcomes(CMDPSTATE* state) 02967 { 02968 02969 int cost; 02970 02971 #if DEBUG 02972 if(state->StateID >= (int)StateID2CoordTable.size()) 02973 { 02974 ROS_ERROR("ERROR in Env... function: stateID illegal"); 02975 throw new SBPL_Exception(); 02976 } 02977 02978 if((int)state->Actions.size() != 0) 02979 { 02980 ROS_ERROR("ERROR in Env_setAllActionsandAllOutcomes: actions already exist for the state"); 02981 throw new SBPL_Exception(); 02982 } 02983 #endif 02984 02985 02986 //goal state should be absorbing 02987 if(state->StateID == EnvNAVXYTHETACARTLAT.goalstateid) 02988 return; 02989 02990 //get X, Y for the state 02991 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = StateID2CoordTable[state->StateID]; 02992 02993 //iterate through actions 02994 for (int aind = 0; aind < EnvNAVXYTHETACARTLATCfg.actionwidth; aind++) 02995 { 02996 EnvNAVXYTHETACARTLATAction_t* nav3daction = &EnvNAVXYTHETACARTLATCfg.ActionsV[(int)HashEntry->Theta][aind]; 02997 int newX = HashEntry->X + nav3daction->dX; 02998 int newY = HashEntry->Y + nav3daction->dY; 02999 int newTheta = NORMALIZEDISCTHETA(nav3daction->endtheta, NAVXYTHETACARTLAT_THETADIRS); 03000 int newCartAngle = NORMALIZEDISCTHETA(nav3daction->endcartangle, CART_THETADIRS); 03001 03002 //skip the invalid cells 03003 if(!IsValidCell(newX, newY)) 03004 continue; 03005 03006 //get cost 03007 cost = GetActionCost(HashEntry->X, HashEntry->Y, HashEntry->Theta, HashEntry->CartAngle, nav3daction); 03008 if(cost >= INFINITECOST) 03009 continue; 03010 03011 //add the action 03012 CMDPACTION* action = state->AddAction(aind); 03013 03014 #if TIME_DEBUG 03015 clock_t currenttime = clock(); 03016 #endif 03017 03018 EnvNAVXYTHETACARTLATHashEntry_t* OutHashEntry; 03019 if((OutHashEntry = (this->*GetHashEntry)(newX, newY, newTheta, newCartAngle)) == NULL) 03020 { 03021 //have to create a new entry 03022 OutHashEntry = (this->*CreateNewHashEntry)(newX, newY, newTheta, newCartAngle); 03023 } 03024 action->AddOutcome(OutHashEntry->stateID, cost, 1.0); 03025 03026 #if TIME_DEBUG 03027 time3_addallout += clock()-currenttime; 03028 #endif 03029 03030 } 03031 } 03032 03033 03034 void EnvironmentNAVXYTHETACARTLAT::GetPredsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *preds_of_changededgesIDV) 03035 { 03036 nav2dcell_t cell; 03037 EnvNAVXYTHETACARTLAT3Dcell_t affectedcell; 03038 EnvNAVXYTHETACARTLATHashEntry_t* affectedHashEntry; 03039 03040 //increment iteration for processing savings 03041 iteration++; 03042 03043 for(int i = 0; i < (int)changedcellsV->size(); i++) 03044 { 03045 cell = changedcellsV->at(i); 03046 03047 //now iterate over all states that could potentially be affected 03048 for(int sind = 0; sind < (int)affectedpredstatesV.size(); sind++) 03049 { 03050 affectedcell = affectedpredstatesV.at(sind); 03051 03052 //translate to correct for the offset 03053 affectedcell.x = affectedcell.x + cell.x; 03054 affectedcell.y = affectedcell.y + cell.y; 03055 03056 //insert only if it was actually generated 03057 affectedHashEntry = (this->*GetHashEntry)(affectedcell.x, affectedcell.y, affectedcell.theta, affectedcell.cartangle); 03058 if(affectedHashEntry != NULL && affectedHashEntry->iteration < iteration) 03059 { 03060 preds_of_changededgesIDV->push_back(affectedHashEntry->stateID); 03061 affectedHashEntry->iteration = iteration; //mark as already inserted 03062 } 03063 } 03064 } 03065 } 03066 03067 void EnvironmentNAVXYTHETACARTLAT::GetSuccsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *succs_of_changededgesIDV) 03068 { 03069 nav2dcell_t cell; 03070 EnvNAVXYTHETACARTLAT3Dcell_t affectedcell; 03071 EnvNAVXYTHETACARTLATHashEntry_t* affectedHashEntry; 03072 03073 ROS_ERROR("getsuccs is not supported currently"); 03074 return; 03075 03076 //increment iteration for processing savings 03077 iteration++; 03078 03079 //TODO - check 03080 for(int i = 0; i < (int)changedcellsV->size(); i++) 03081 { 03082 cell = changedcellsV->at(i); 03083 03084 //now iterate over all states that could potentially be affected 03085 for(int sind = 0; sind < (int)affectedsuccstatesV.size(); sind++) 03086 { 03087 affectedcell = affectedsuccstatesV.at(sind); 03088 03089 //translate to correct for the offset 03090 affectedcell.x = affectedcell.x + cell.x; 03091 affectedcell.y = affectedcell.y + cell.y; 03092 03093 //insert only if it was actually generated 03094 affectedHashEntry = (this->*GetHashEntry)(affectedcell.x, affectedcell.y, affectedcell.theta, affectedcell.cartangle); 03095 if(affectedHashEntry != NULL && affectedHashEntry->iteration < iteration) 03096 { 03097 succs_of_changededgesIDV->push_back(affectedHashEntry->stateID); 03098 affectedHashEntry->iteration = iteration; //mark as already inserted 03099 } 03100 } 03101 } 03102 } 03103 03104 void EnvironmentNAVXYTHETACARTLAT::InitializeEnvironment() 03105 { 03106 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry; 03107 03108 int maxsize = EnvNAVXYTHETACARTLATCfg.EnvWidth_c*EnvNAVXYTHETACARTLATCfg.EnvHeight_c*NAVXYTHETACARTLAT_THETADIRS*CART_THETADIRS;//Needs to be changed 03109 03110 if(maxsize <= SBPL_XYTHETACARTLAT_MAXSTATESFORLOOKUP) 03111 { 03112 ROS_DEBUG("environment stores states in lookup table"); 03113 03114 Coord2StateIDHashTable_lookup = new EnvNAVXYTHETACARTLATHashEntry_t*[maxsize]; 03115 for(int i = 0; i < maxsize; i++) 03116 Coord2StateIDHashTable_lookup[i] = NULL; 03117 GetHashEntry = &EnvironmentNAVXYTHETACARTLAT::GetHashEntry_lookup; 03118 CreateNewHashEntry = &EnvironmentNAVXYTHETACARTLAT::CreateNewHashEntry_lookup; 03119 03120 //not using hash table 03121 HashTableSize = 0; 03122 Coord2StateIDHashTable = NULL; 03123 } 03124 else 03125 { 03126 ROS_DEBUG("environment stores states in hashtable"); 03127 03128 //initialize the map from Coord to StateID 03129 HashTableSize = 4*1024*1024; //should be power of two 03130 Coord2StateIDHashTable = new vector<EnvNAVXYTHETACARTLATHashEntry_t*>[HashTableSize]; 03131 GetHashEntry = &EnvironmentNAVXYTHETACARTLAT::GetHashEntry_hash; 03132 CreateNewHashEntry = &EnvironmentNAVXYTHETACARTLAT::CreateNewHashEntry_hash; 03133 03134 //not using hash 03135 Coord2StateIDHashTable_lookup = NULL; 03136 } 03137 03138 03139 //initialize the map from StateID to Coord 03140 StateID2CoordTable.clear(); 03141 03142 //create start state 03143 if((HashEntry = (this->*GetHashEntry)(EnvNAVXYTHETACARTLATCfg.StartX_c, EnvNAVXYTHETACARTLATCfg.StartY_c, EnvNAVXYTHETACARTLATCfg.StartTheta, EnvNAVXYTHETACARTLATCfg.StartCartAngle)) == NULL){ 03144 //have to create a new entry 03145 HashEntry = (this->*CreateNewHashEntry)(EnvNAVXYTHETACARTLATCfg.StartX_c, EnvNAVXYTHETACARTLATCfg.StartY_c, EnvNAVXYTHETACARTLATCfg.StartTheta, EnvNAVXYTHETACARTLATCfg.StartCartAngle); 03146 } 03147 EnvNAVXYTHETACARTLAT.startstateid = HashEntry->stateID; 03148 03149 //create goal state 03150 if((HashEntry = (this->*GetHashEntry)(EnvNAVXYTHETACARTLATCfg.EndX_c, EnvNAVXYTHETACARTLATCfg.EndY_c, EnvNAVXYTHETACARTLATCfg.EndTheta, EnvNAVXYTHETACARTLATCfg.EndCartAngle)) == NULL){ 03151 //have to create a new entry 03152 HashEntry = (this->*CreateNewHashEntry)(EnvNAVXYTHETACARTLATCfg.EndX_c, EnvNAVXYTHETACARTLATCfg.EndY_c, EnvNAVXYTHETACARTLATCfg.EndTheta, EnvNAVXYTHETACARTLATCfg.EndCartAngle); 03153 } 03154 EnvNAVXYTHETACARTLAT.goalstateid = HashEntry->stateID; 03155 03156 //initialized 03157 EnvNAVXYTHETACARTLAT.bInitialized = true; 03158 03159 } 03160 03161 03162 //examples of hash functions: map state coordinates onto a hash value 03163 //#define GETHASHBIN(X, Y) (Y*WIDTH_Y+X) 03164 //here we have state coord: <X1, X2, X3, X4> 03165 unsigned int EnvironmentNAVXYTHETACARTLAT::GETHASHBIN(unsigned int X1, unsigned int X2, unsigned int Theta, unsigned int CartAngle) 03166 { 03167 return inthash(inthash(X1)+(inthash(X2)<<1)+(inthash(Theta)<<2)+(inthash(CartAngle)<<3)) & (HashTableSize-1); 03168 } 03169 03170 void EnvironmentNAVXYTHETACARTLAT::PrintHashTableHist(FILE* fOut) 03171 { 03172 int s0=0, s1=0, s50=0, s100=0, s200=0, s300=0, slarge=0; 03173 03174 for(int j = 0; j < HashTableSize; j++) 03175 { 03176 if((int)Coord2StateIDHashTable[j].size() == 0) 03177 s0++; 03178 else if((int)Coord2StateIDHashTable[j].size() < 5) 03179 s1++; 03180 else if((int)Coord2StateIDHashTable[j].size() < 25) 03181 s50++; 03182 else if((int)Coord2StateIDHashTable[j].size() < 50) 03183 s100++; 03184 else if((int)Coord2StateIDHashTable[j].size() < 100) 03185 s200++; 03186 else if((int)Coord2StateIDHashTable[j].size() < 400) 03187 s300++; 03188 else 03189 slarge++; 03190 } 03191 SBPL_FPRINTF(fOut, "hash table histogram: 0:%d, <5:%d, <25:%d, <50:%d, <100:%d, <400:%d, >400:%d", 03192 s0,s1, s50, s100, s200,s300,slarge); 03193 } 03194 03195 int EnvironmentNAVXYTHETACARTLAT::GetFromToHeuristic(int FromStateID, int ToStateID) 03196 { 03197 03198 #if USE_HEUR==0 03199 return 0; 03200 #endif 03201 03202 03203 #if DEBUG 03204 if(FromStateID >= (int)StateID2CoordTable.size() 03205 || ToStateID >= (int)StateID2CoordTable.size()) 03206 { 03207 ROS_ERROR("ERROR in EnvNAVXYTHETACARTLAT... function: stateID illegal"); 03208 throw new SBPL_Exception(); 03209 } 03210 #endif 03211 03212 //get X, Y for the state 03213 EnvNAVXYTHETACARTLATHashEntry_t* FromHashEntry = StateID2CoordTable[FromStateID]; 03214 EnvNAVXYTHETACARTLATHashEntry_t* ToHashEntry = StateID2CoordTable[ToStateID]; 03215 03216 //TODO - check if one of the gridsearches already computed and then use it. 03217 03218 03219 return (int)(NAVXYTHETACARTLAT_COSTMULT_MTOMM*EuclideanDistance_m(FromHashEntry->X, FromHashEntry->Y, ToHashEntry->X, ToHashEntry->Y)/EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs); 03220 03221 } 03222 03223 03224 int EnvironmentNAVXYTHETACARTLAT::GetGoalHeuristic(int stateID) 03225 { 03226 #if USE_HEUR==0 03227 return 0; 03228 #endif 03229 03230 #if DEBUG 03231 if(stateID >= (int)StateID2CoordTable.size()) 03232 { 03233 ROS_ERROR("ERROR in EnvNAVXYTHETACARTLAT... function: stateID illegal"); 03234 throw new SBPL_Exception(); 03235 } 03236 #endif 03237 03238 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = StateID2CoordTable[stateID]; 03239 int h2D = grid2Dsearchfromgoal->getlowerboundoncostfromstart_inmm(HashEntry->X, HashEntry->Y); //computes distances from start state that is grid2D, so it is EndX_c EndY_c 03240 int hEuclid = (int)(NAVXYTHETACARTLAT_COSTMULT_MTOMM*EuclideanDistance_m(HashEntry->X, HashEntry->Y, EnvNAVXYTHETACARTLATCfg.EndX_c, EnvNAVXYTHETACARTLATCfg.EndY_c)); 03241 03242 //define this function if it is used in the planner (heuristic backward search would use it) 03243 return (int)(((double)__max(h2D,hEuclid))/EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs); 03244 03245 } 03246 03247 03248 int EnvironmentNAVXYTHETACARTLAT::GetStartHeuristic(int stateID) 03249 { 03250 03251 03252 #if USE_HEUR==0 03253 return 0; 03254 #endif 03255 03256 03257 #if DEBUG 03258 if(stateID >= (int)StateID2CoordTable.size()) 03259 { 03260 ROS_ERROR("ERROR in EnvNAVXYTHETACARTLAT... function: stateID illegal"); 03261 throw new SBPL_Exception(); 03262 } 03263 #endif 03264 03265 EnvNAVXYTHETACARTLATHashEntry_t* HashEntry = StateID2CoordTable[stateID]; 03266 int h2D = grid2Dsearchfromstart->getlowerboundoncostfromstart_inmm(HashEntry->X, HashEntry->Y); 03267 int hEuclid = (int)(NAVXYTHETACARTLAT_COSTMULT_MTOMM*EuclideanDistance_m(EnvNAVXYTHETACARTLATCfg.StartX_c, EnvNAVXYTHETACARTLATCfg.StartY_c, HashEntry->X, HashEntry->Y)); 03268 03269 //define this function if it is used in the planner (heuristic backward search would use it) 03270 return (int)(((double)__max(h2D,hEuclid))/EnvNAVXYTHETACARTLATCfg.nominalvel_mpersecs); 03271 03272 } 03273 03274 int EnvironmentNAVXYTHETACARTLAT::SizeofCreatedEnv() 03275 { 03276 return (int)StateID2CoordTable.size(); 03277 03278 } 03279 //------------------------------------------------------------------------------