$search
00001 /* 00002 * Copyright (c) 2008, Maxim Likhachev 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the University of Pennsylvania nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 #include <iostream> 00030 using namespace std; 00031 00032 #include "../sbpl/headers.h" 00033 00034 00035 void PrintUsage(char *argv[]) 00036 { 00037 SBPL_PRINTF("USAGE: %s <cfg file> [motionprimitivesfile.mprim for xythetalattice planning]\n", argv[0]); 00038 } 00039 00040 00041 int plan2d(int argc, char *argv[]) 00042 { 00043 00044 int bRet = 0; 00045 double allocated_time_secs = 100.0; //in seconds 00046 MDPConfig MDPCfg; 00047 bool bsearchuntilfirstsolution = true; 00048 00049 //Initialize Environment (should be called before initializing anything else) 00050 EnvironmentNAV2D environment_nav2D; 00051 if(!environment_nav2D.InitializeEnv(argv[1])) 00052 { 00053 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00054 throw new SBPL_Exception(); 00055 } 00056 00057 //Initialize MDP Info 00058 if(!environment_nav2D.InitializeMDPCfg(&MDPCfg)) 00059 { 00060 SBPL_ERROR("ERROR: InitializeMDPCfg failed\n"); 00061 throw new SBPL_Exception(); 00062 } 00063 00064 00065 //plan a path 00066 vector<int> solution_stateIDs_V; 00067 bool bforwardsearch = false; 00068 ARAPlanner planner(&environment_nav2D, bforwardsearch); 00069 00070 //set search mode 00071 planner.set_search_mode(bsearchuntilfirstsolution); 00072 00073 00074 if(planner.set_start(MDPCfg.startstateid) == 0) 00075 { 00076 SBPL_ERROR("ERROR: failed to set start state\n"); 00077 throw new SBPL_Exception(); 00078 } 00079 00080 if(planner.set_goal(MDPCfg.goalstateid) == 0) 00081 { 00082 SBPL_ERROR("ERROR: failed to set goal state\n"); 00083 throw new SBPL_Exception(); 00084 } 00085 00086 planner.set_initialsolution_eps(3.0); 00087 00088 SBPL_PRINTF("start planning...\n"); 00089 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00090 SBPL_PRINTF("done planning\n"); 00091 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00092 00093 environment_nav2D.PrintTimeStat(stdout); 00094 00095 /* 00096 SBPL_PRINTF("start planning...\n"); 00097 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00098 SBPL_PRINTF("done planning\n"); 00099 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00100 00101 environment_nav2D.PrintTimeStat(stdout); 00102 00103 SBPL_PRINTF("start planning...\n"); 00104 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00105 SBPL_PRINTF("done planning\n"); 00106 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00107 00108 environment_nav2D.PrintTimeStat(stdout); 00109 00110 SBPL_PRINTF("start planning...\n"); 00111 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00112 SBPL_PRINTF("done planning\n"); 00113 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00114 00115 environment_nav2D.PrintTimeStat(stdout); 00116 00117 SBPL_PRINTF("start planning...\n"); 00118 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00119 SBPL_PRINTF("done planning\n"); 00120 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00121 00122 environment_nav2D.PrintTimeStat(stdout); 00123 00124 SBPL_PRINTF("start planning...\n"); 00125 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00126 SBPL_PRINTF("done planning\n"); 00127 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00128 */ 00129 00130 #ifndef ROS 00131 const char* sol = "sol.txt"; 00132 #endif 00133 FILE* fSol = SBPL_FOPEN(sol, "w"); 00134 if(fSol == NULL){ 00135 SBPL_ERROR("ERROR: could not open solution file\n"); 00136 throw new SBPL_Exception(); 00137 } 00138 for(unsigned int i = 0; i < solution_stateIDs_V.size(); i++) { 00139 environment_nav2D.PrintState(solution_stateIDs_V[i], false, fSol); 00140 } 00141 SBPL_FCLOSE(fSol); 00142 00143 environment_nav2D.PrintTimeStat(stdout); 00144 00145 //print a path 00146 if(bRet) 00147 { 00148 //print the solution 00149 SBPL_PRINTF("Solution is found\n"); 00150 } 00151 else 00152 SBPL_PRINTF("Solution does not exist\n"); 00153 00154 SBPL_FFLUSH(NULL); 00155 00156 00157 return bRet; 00158 } 00159 00160 int plan2duu(int argc, char *argv[]) 00161 { 00162 00163 int bRet = 0; 00164 double allocated_time_secs = 100.0; //in seconds 00165 MDPConfig MDPCfg; 00166 00167 //Initialize Environment (should be called before initializing anything else) 00168 EnvironmentNAV2DUU environment_nav2Duu; 00169 if(!environment_nav2Duu.InitializeEnv(argv[1])) 00170 { 00171 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00172 throw new SBPL_Exception(); 00173 } 00174 00175 //Initialize MDP Info 00176 if(!environment_nav2Duu.InitializeMDPCfg(&MDPCfg)) 00177 { 00178 SBPL_ERROR("ERROR: InitializeMDPCfg failed\n"); 00179 throw new SBPL_Exception(); 00180 } 00181 00182 00183 //create the planner 00184 PPCPPlanner planner(&environment_nav2Duu, environment_nav2Duu.SizeofCreatedEnv(), environment_nav2Duu.SizeofH()); 00185 00186 //set start and goal 00187 if(planner.set_start(MDPCfg.startstateid) == 0) 00188 { 00189 SBPL_ERROR("ERROR: failed to set start state\n"); 00190 throw new SBPL_Exception(); 00191 } 00192 if(planner.set_goal(MDPCfg.goalstateid) == 0) 00193 { 00194 SBPL_ERROR("ERROR: failed to set goal state\n"); 00195 throw new SBPL_Exception(); 00196 } 00197 00198 00199 SBPL_PRINTF("start planning...\n"); 00200 float ExpectedCost, ProbofReachGoal; 00201 vector<sbpl_PolicyStatewithBinaryh_t> SolutionPolicy; 00202 bRet = planner.replan(allocated_time_secs, &SolutionPolicy, &ExpectedCost, &ProbofReachGoal); 00203 SBPL_PRINTF("done planning\n"); 00204 00205 00206 if(bRet) 00207 { 00208 //print the solution 00209 SBPL_PRINTF("Solution is found: exp. cost=%f probofreachgoal=%f\n", ExpectedCost, ProbofReachGoal); 00210 } 00211 else 00212 SBPL_PRINTF("Solution does not exist\n"); 00213 00214 SBPL_FFLUSH(NULL); 00215 00216 00217 return bRet; 00218 } 00219 00220 00221 int planxythetalat(int argc, char *argv[]) 00222 { 00223 00224 int bRet = 0; 00225 double allocated_time_secs = 10; //in seconds 00226 MDPConfig MDPCfg; 00227 bool bsearchuntilfirstsolution = false; 00228 00229 //set the perimeter of the robot (it is given with 0,0,0 robot ref. point for which planning is done) 00230 vector<sbpl_2Dpt_t> perimeterptsV; 00231 sbpl_2Dpt_t pt_m; 00232 double halfwidth = 0.01; //0.3; 00233 double halflength = 0.01; //0.45; 00234 pt_m.x = -halflength; 00235 pt_m.y = -halfwidth; 00236 perimeterptsV.push_back(pt_m); 00237 pt_m.x = halflength; 00238 pt_m.y = -halfwidth; 00239 perimeterptsV.push_back(pt_m); 00240 pt_m.x = halflength; 00241 pt_m.y = halfwidth; 00242 perimeterptsV.push_back(pt_m); 00243 pt_m.x = -halflength; 00244 pt_m.y = halfwidth; 00245 perimeterptsV.push_back(pt_m); 00246 00247 00248 //clear perimeter 00249 //perimeterptsV.clear(); 00250 //pt_m.x = 0.0; 00251 //pt_m.y = 0.0; 00252 //perimeterptsV.push_back(pt_m); 00253 00254 //Initialize Environment (should be called before initializing anything else) 00255 EnvironmentNAVXYTHETALAT environment_navxythetalat; 00256 00257 if(argc == 3) 00258 { 00259 if(!environment_navxythetalat.InitializeEnv(argv[1], perimeterptsV, argv[2])) 00260 { 00261 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00262 throw new SBPL_Exception(); 00263 } 00264 } 00265 else 00266 { 00267 if(!environment_navxythetalat.InitializeEnv(argv[1], perimeterptsV, NULL)) 00268 { 00269 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00270 throw new SBPL_Exception(); 00271 } 00272 } 00273 00274 //Initialize MDP Info 00275 if(!environment_navxythetalat.InitializeMDPCfg(&MDPCfg)) 00276 { 00277 SBPL_ERROR("ERROR: InitializeMDPCfg failed\n"); 00278 throw new SBPL_Exception(); 00279 } 00280 00281 00282 //plan a path 00283 vector<int> solution_stateIDs_V; 00284 bool bforwardsearch = false; 00285 ADPlanner planner(&environment_navxythetalat, bforwardsearch); 00286 00287 if(planner.set_start(MDPCfg.startstateid) == 0) 00288 { 00289 SBPL_ERROR("ERROR: failed to set start state\n"); 00290 throw new SBPL_Exception(); 00291 } 00292 00293 if(planner.set_goal(MDPCfg.goalstateid) == 0) 00294 { 00295 SBPL_ERROR("ERROR: failed to set goal state\n"); 00296 throw new SBPL_Exception(); 00297 } 00298 planner.set_initialsolution_eps(3.0); 00299 00300 //set search mode 00301 planner.set_search_mode(bsearchuntilfirstsolution); 00302 00303 SBPL_PRINTF("start planning...\n"); 00304 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00305 SBPL_PRINTF("done planning\n"); 00306 SBPL_PRINTF("size of solution=%d\n",(unsigned int)solution_stateIDs_V.size()); 00307 00308 environment_navxythetalat.PrintTimeStat(stdout); 00309 00310 /* 00311 if(planner.set_start(environment_navxythetalat.SetStart(1.6,0.5,0)) == 0) 00312 { 00313 SBPL_ERROR("ERROR: failed to set start state\n"); 00314 throw new SBPL_Exception(); 00315 } 00316 00317 00318 SBPL_PRINTF("start planning...\n"); 00319 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00320 SBPL_PRINTF("done planning\n"); 00321 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00322 00323 environment_navxythetalat.PrintTimeStat(stdout); 00324 00325 00326 SBPL_PRINTF("start planning...\n"); 00327 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00328 SBPL_PRINTF("done planning\n"); 00329 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00330 00331 environment_navxythetalat.PrintTimeStat(stdout); 00332 00333 SBPL_PRINTF("start planning...\n"); 00334 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00335 SBPL_PRINTF("done planning\n"); 00336 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00337 00338 environment_navxythetalat.PrintTimeStat(stdout); 00339 00340 SBPL_PRINTF("start planning...\n"); 00341 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00342 SBPL_PRINTF("done planning\n"); 00343 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00344 00345 environment_navxythetalat.PrintTimeStat(stdout); 00346 00347 SBPL_PRINTF("start planning...\n"); 00348 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00349 SBPL_PRINTF("done planning\n"); 00350 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00351 */ 00352 00353 #ifndef ROS 00354 const char* sol = "sol.txt"; 00355 #endif 00356 FILE* fSol = SBPL_FOPEN(sol, "w"); 00357 if(fSol == NULL){ 00358 SBPL_ERROR("ERROR: could not open solution file\n"); 00359 throw new SBPL_Exception(); 00360 } 00361 vector<EnvNAVXYTHETALAT3Dpt_t> xythetaPath; 00362 environment_navxythetalat.ConvertStateIDPathintoXYThetaPath(&solution_stateIDs_V, &xythetaPath); 00363 SBPL_PRINTF("solution size=%d\n", (unsigned int)xythetaPath.size()); 00364 for(unsigned int i = 0; i < xythetaPath.size(); i++) { 00365 SBPL_FPRINTF(fSol, "%.3f %.3f %.3f\n", xythetaPath.at(i).x, xythetaPath.at(i).y, xythetaPath.at(i).theta); 00366 } 00367 SBPL_FCLOSE(fSol); 00368 00369 environment_navxythetalat.PrintTimeStat(stdout); 00370 00371 //print a path 00372 if(bRet) 00373 { 00374 //print the solution 00375 SBPL_PRINTF("Solution is found\n"); 00376 } 00377 else 00378 SBPL_PRINTF("Solution does not exist\n"); 00379 00380 SBPL_FFLUSH(NULL); 00381 00382 00383 return bRet; 00384 } 00385 00386 //planning with multiple levels x,y,theta lattice (for example, base and upper body) 00387 //there are no additional degrees of freedom. 00388 //It is just that each level may have a different footprint 00389 //and should be checked against the cost map at corresponding height 00390 //It is useful for doing planning for navigation by a tall ground robot operating in a cluttered 3D map 00391 int planxythetamlevlat(int argc, char *argv[]) 00392 { 00393 00394 int bRet = 0; 00395 double allocated_time_secs = 10; //in seconds 00396 MDPConfig MDPCfg; 00397 bool bsearchuntilfirstsolution = false; 00398 00399 //set the perimeter of the robot (it is given with 0,0,0 robot ref. point for which planning is done) 00400 //this is for the default level - base level 00401 vector<sbpl_2Dpt_t> perimeterptsV; 00402 sbpl_2Dpt_t pt_m; 00403 double halfwidth = 0.3; //0.3; 00404 double halflength = 0.25; //0.45; 00405 pt_m.x = -halflength; 00406 pt_m.y = -halfwidth; 00407 perimeterptsV.push_back(pt_m); 00408 pt_m.x = halflength; 00409 pt_m.y = -halfwidth; 00410 perimeterptsV.push_back(pt_m); 00411 pt_m.x = halflength; 00412 pt_m.y = halfwidth; 00413 perimeterptsV.push_back(pt_m); 00414 pt_m.x = -halflength; 00415 pt_m.y = halfwidth; 00416 perimeterptsV.push_back(pt_m); 00417 00418 //clear perimeter 00419 //perimeterptsV.clear(); 00420 //pt_m.x = 0.0; 00421 //pt_m.y = 0.0; 00422 //perimeterptsV.push_back(pt_m); 00423 00424 //Initialize Environment (should be called before initializing anything else) 00425 EnvironmentNAVXYTHETAMLEVLAT environment_navxythetalat; 00426 00427 if(argc == 3) 00428 { 00429 if(!environment_navxythetalat.InitializeEnv(argv[1], perimeterptsV, argv[2])) 00430 { 00431 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00432 throw new SBPL_Exception(); 00433 } 00434 } 00435 else 00436 { 00437 if(!environment_navxythetalat.InitializeEnv(argv[1], perimeterptsV, NULL)) 00438 { 00439 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00440 throw new SBPL_Exception(); 00441 } 00442 } 00443 00444 00445 //this is for the second level - upper body level 00446 vector<sbpl_2Dpt_t> perimeterptsVV[2]; 00447 perimeterptsVV[0].clear(); 00448 halfwidth = 0.3; 00449 halflength = 0.75; 00450 pt_m.x = -halflength; 00451 pt_m.y = -halfwidth; 00452 perimeterptsVV[0].push_back(pt_m); 00453 pt_m.x = halflength; 00454 pt_m.y = -halfwidth; 00455 perimeterptsVV[0].push_back(pt_m); 00456 pt_m.x = halflength; 00457 pt_m.y = halfwidth; 00458 perimeterptsVV[0].push_back(pt_m); 00459 pt_m.x = -halflength; 00460 pt_m.y = halfwidth; 00461 perimeterptsVV[0].push_back(pt_m); 00462 00463 00464 //enable the second level 00465 int numofaddlevels = 1; 00466 SBPL_PRINTF("Number of additional levels = %d\n", numofaddlevels); 00467 unsigned char cost_inscribed_thresh_addlevels[2]; //size should be at least numofaddlevels 00468 unsigned char cost_possibly_circumscribed_thresh_addlevels[2]; //size should be at least numofaddlevels 00469 cost_inscribed_thresh_addlevels[0] = 255; //no costs are indicative of whether a cell is within inner circle 00470 cost_possibly_circumscribed_thresh_addlevels[0] = 0; //no costs are indicative of whether a cell is within outer circle 00471 cost_inscribed_thresh_addlevels[1] = 255; //no costs are indicative of whether a cell is within inner circle 00472 cost_possibly_circumscribed_thresh_addlevels[1] = 0; //no costs are indicative of whether a cell is within outer circle 00473 if(!environment_navxythetalat.InitializeAdditionalLevels(numofaddlevels, perimeterptsVV, 00474 cost_inscribed_thresh_addlevels, cost_possibly_circumscribed_thresh_addlevels)) 00475 { 00476 SBPL_ERROR("ERROR: InitializeAdditionalLevels failed with numofaddlevels=%d\n", numofaddlevels); 00477 throw new SBPL_Exception(); 00478 00479 } 00480 00481 //set the map for the second level (index parameter for the additional levels and is zero based) 00482 //for this example, we pass in the same map as the map for the base. In general, it can be a totally different map 00483 //as it corresponds to a different level 00484 //NOTE: this map has to have costs set correctly with respect to inner and outer radii of the robot 00485 //if the second level of the robot has these radii different than at the base level, then costs 00486 //should reflect this 00487 //(see explanation for cost_possibly_circumscribed_thresh and cost_inscribed_thresh parameters in environment_navxythetalat.h file) 00488 int addlevind = 0; 00489 if(!environment_navxythetalat.Set2DMapforAddLev( 00490 (const unsigned char**)(environment_navxythetalat.GetEnvNavConfig()->Grid2D),addlevind)) 00491 { 00492 SBPL_ERROR("ERROR: Setting Map for the Additional Level failed with level %d\n", addlevind); 00493 throw new SBPL_Exception(); 00494 00495 } 00496 00497 //Initialize MDP Info 00498 if(!environment_navxythetalat.InitializeMDPCfg(&MDPCfg)) 00499 { 00500 SBPL_ERROR("ERROR: InitializeMDPCfg failed\n"); 00501 throw new SBPL_Exception(); 00502 } 00503 00504 00505 //plan a path 00506 vector<int> solution_stateIDs_V; 00507 bool bforwardsearch = false; 00508 ADPlanner planner(&environment_navxythetalat, bforwardsearch); 00509 00510 if(planner.set_start(MDPCfg.startstateid) == 0) 00511 { 00512 SBPL_ERROR("ERROR: failed to set start state\n"); 00513 throw new SBPL_Exception(); 00514 } 00515 00516 if(planner.set_goal(MDPCfg.goalstateid) == 0) 00517 { 00518 SBPL_ERROR("ERROR: failed to set goal state\n"); 00519 throw new SBPL_Exception(); 00520 } 00521 planner.set_initialsolution_eps(3.0); 00522 00523 //set search mode 00524 planner.set_search_mode(bsearchuntilfirstsolution); 00525 00526 SBPL_PRINTF("start planning...\n"); 00527 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 00528 SBPL_PRINTF("done planning\n"); 00529 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 00530 00531 environment_navxythetalat.PrintTimeStat(stdout); 00532 00533 #ifndef ROS 00534 const char* sol = "sol.txt"; 00535 #endif 00536 FILE* fSol = SBPL_FOPEN(sol, "w"); 00537 if(fSol == NULL){ 00538 SBPL_ERROR("ERROR: could not open solution file\n"); 00539 throw new SBPL_Exception(); 00540 } 00541 vector<EnvNAVXYTHETALAT3Dpt_t> xythetaPath; 00542 environment_navxythetalat.ConvertStateIDPathintoXYThetaPath(&solution_stateIDs_V, &xythetaPath); 00543 SBPL_PRINTF("solution size=%d\n", (unsigned int)xythetaPath.size()); 00544 for(unsigned int i = 0; i < xythetaPath.size(); i++) { 00545 SBPL_FPRINTF(fSol, "%.3f %.3f %.3f\n", xythetaPath.at(i).x, xythetaPath.at(i).y, xythetaPath.at(i).theta); 00546 } 00547 SBPL_FCLOSE(fSol); 00548 00549 environment_navxythetalat.PrintTimeStat(stdout); 00550 00551 //print a path 00552 if(bRet) 00553 { 00554 //print the solution 00555 SBPL_PRINTF("Solution is found\n"); 00556 } 00557 else 00558 SBPL_PRINTF("Solution does not exist\n"); 00559 00560 SBPL_FFLUSH(NULL); 00561 00562 00563 return bRet; 00564 } 00565 00566 00567 00568 00569 int planandnavigate2d(int argc, char *argv[]) 00570 { 00571 double allocated_time_secs_foreachplan = 0.2; //in seconds 00572 MDPConfig MDPCfg; 00573 EnvironmentNAV2D environment_nav2D; 00574 EnvironmentNAV2D trueenvironment_nav2D; 00575 int size_x=-1,size_y=-1; 00576 int startx = 0, starty = 0; 00577 int goalx=-1, goaly=-1; 00578 #ifndef ROS 00579 const char* sol = "sol.txt"; 00580 #endif 00581 FILE* fSol = SBPL_FOPEN(sol, "w"); 00582 if(fSol == NULL){ 00583 SBPL_ERROR("ERROR: could not open solution file\n"); 00584 throw new SBPL_Exception(); 00585 } 00586 int dx[8] = {-1, -1, -1, 0, 0, 1, 1, 1}; 00587 int dy[8] = {-1, 0, 1, -1, 1, -1, 0, 1}; 00588 bool bPrint = true; 00589 int x,y; 00590 vector<int> preds_of_changededgesIDV; 00591 vector<nav2dcell_t> changedcellsV; 00592 nav2dcell_t nav2dcell; 00593 int i; 00594 unsigned char obsthresh = 0; 00595 //srand(0); 00596 int plantime_over1secs=0, plantime_over0p5secs=0, plantime_over0p1secs=0, plantime_over0p05secs=0, plantime_below0p05secs=0; 00597 00598 //set parameters - should be done before initialization 00599 if(!trueenvironment_nav2D.SetEnvParameter("is16connected", 1)) 00600 { 00601 SBPL_ERROR("ERROR: failed to set parameters\n"); 00602 throw new SBPL_Exception(); 00603 } 00604 if(!environment_nav2D.SetEnvParameter("is16connected", 1)) 00605 { 00606 SBPL_ERROR("ERROR: failed to set parameters\n"); 00607 throw new SBPL_Exception(); 00608 } 00609 00610 00611 //initialize true map and robot map 00612 if(!trueenvironment_nav2D.InitializeEnv(argv[1])) 00613 { 00614 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00615 throw new SBPL_Exception(); 00616 } 00617 trueenvironment_nav2D.GetEnvParms(&size_x, &size_y, &startx, &starty, &goalx, &goaly, &obsthresh); 00618 unsigned char* map = (unsigned char*)calloc(size_x*size_y, sizeof(unsigned char)); 00619 00620 //print the map 00621 if(bPrint) SBPL_PRINTF("true map:\n"); 00622 for(y = 0; bPrint && y < size_y; y++){ 00623 for(x = 0; x < size_x; x++){ 00624 SBPL_PRINTF("%d ", (int)trueenvironment_nav2D.IsObstacle(x,y)); 00625 } 00626 SBPL_PRINTF("\n"); 00627 } 00628 if(bPrint) SBPL_PRINTF("System Pause (return=%d)\n",system("pause")); 00629 00630 //Initialize Environment (should be called before initializing anything else) 00631 if(!environment_nav2D.InitializeEnv(size_x, size_y, map, startx, starty, goalx, goaly, obsthresh)){ 00632 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00633 throw new SBPL_Exception(); 00634 } 00635 00636 //Initialize MDP Info 00637 if(!environment_nav2D.InitializeMDPCfg(&MDPCfg)) 00638 { 00639 SBPL_ERROR("ERROR: InitializeMDPCfg failed\n"); 00640 throw new SBPL_Exception(); 00641 } 00642 00643 00644 //create a planner 00645 vector<int> solution_stateIDs_V; 00646 bool bforwardsearch = false; 00647 //ARAPlanner planner(&environment_nav2D, bforwardsearch); 00648 ADPlanner planner(&environment_nav2D, bforwardsearch); 00649 00650 planner.set_initialsolution_eps(2.0); 00651 00652 00653 //set the start and goal configurations 00654 if(planner.set_start(MDPCfg.startstateid) == 0) 00655 { 00656 SBPL_ERROR("ERROR: failed to set start state\n"); 00657 throw new SBPL_Exception(); 00658 } 00659 if(planner.set_goal(MDPCfg.goalstateid) == 0) 00660 { 00661 SBPL_ERROR("ERROR: failed to set goal state\n"); 00662 throw new SBPL_Exception(); 00663 } 00664 00665 //now comes the main loop 00666 int goalthresh = 0; 00667 while(abs(startx - goalx) > goalthresh || abs(starty - goaly) > goalthresh){ 00668 00669 //simulate sensor data update 00670 bool bChanges = false; 00671 preds_of_changededgesIDV.clear(); 00672 changedcellsV.clear(); 00673 for(i = 0; i < 8; i++){ 00674 int x = startx + dx[i]; 00675 int y = starty + dy[i]; 00676 if(x < 0 || x >= size_x || y < 0 || y >= size_y) 00677 continue; 00678 int index = x + y*size_x; 00679 unsigned char truecost = trueenvironment_nav2D.GetMapCost(x,y); 00680 if(map[index] != truecost){ 00681 map[index] = truecost; 00682 environment_nav2D.UpdateCost(x,y,map[index]); 00683 SBPL_PRINTF("setting cost[%d][%d] to %d\n", x,y,map[index]); 00684 bChanges = true; 00685 //store the changed cells 00686 nav2dcell.x = x; 00687 nav2dcell.y = y; 00688 changedcellsV.push_back(nav2dcell); 00689 } 00690 } 00691 00692 double TimeStarted = clock(); 00693 00694 if(bChanges){ 00695 //planner.costs_changed(); //use by ARA* planner (non-incremental) 00696 00697 //get the affected states 00698 environment_nav2D.GetPredsofChangedEdges(&changedcellsV, &preds_of_changededgesIDV); 00699 //let know the incremental planner about them 00700 planner.update_preds_of_changededges(&preds_of_changededgesIDV); //use by AD* planner (incremental) 00701 } 00702 00703 00704 SBPL_FPRINTF(fSol, "%d %d ", startx, starty); 00705 00706 //plan a path 00707 bool bPlanExists = false; 00708 while(bPlanExists == false){ 00709 SBPL_PRINTF("new planning...\n"); 00710 bPlanExists = (planner.replan(allocated_time_secs_foreachplan, &solution_stateIDs_V) == 1); 00711 SBPL_PRINTF("done with the solution of size=%d\n", (unsigned int)solution_stateIDs_V.size()); 00712 environment_nav2D.PrintTimeStat(stdout); 00713 00714 //for(unsigned int i = 0; i < solution_stateIDs_V.size(); i++) { 00715 //environment_nav2D.PrintState(solution_stateIDs_V[i], true, fSol); 00716 //} 00717 //SBPL_FPRINTF(fSol, "*********\n"); 00718 } 00719 00720 double plantime_secs = (clock()-TimeStarted)/((double)CLOCKS_PER_SEC); 00721 SBPL_FPRINTF(fSol, "%.5f %.5f\n", plantime_secs, planner.get_solution_eps()); 00722 SBPL_FFLUSH(fSol); 00723 if(plantime_secs > 1.0) 00724 plantime_over1secs++; 00725 else if(plantime_secs > 0.5) 00726 plantime_over0p5secs++; 00727 else if(plantime_secs > 0.1) 00728 plantime_over0p1secs++; 00729 else if(plantime_secs > 0.05) 00730 plantime_over0p05secs++; 00731 else 00732 plantime_below0p05secs++; 00733 00734 //print the map 00735 int startindex = startx + starty*size_x; 00736 int goalindex = goalx + goaly*size_x; 00737 for(y = 0; bPrint && y < size_y; y++){ 00738 for(x = 0; x < size_x; x++){ 00739 int index = x + y*size_x; 00740 00741 //check to see if it is on the path 00742 bool bOnthePath = false; 00743 for(int j = 1; j < (int)solution_stateIDs_V.size(); j++) 00744 { 00745 int newx, newy; 00746 environment_nav2D.GetCoordFromState(solution_stateIDs_V[j], newx, newy); 00747 if(x == newx && y == newy) 00748 bOnthePath = true; 00749 } 00750 00751 if (index != startindex && index != goalindex && !bOnthePath) 00752 SBPL_PRINTF("%3d ", map[index]); 00753 else if(index == startindex) 00754 SBPL_PRINTF(" R "); 00755 else if(index == goalindex) 00756 SBPL_PRINTF(" G "); 00757 else if (bOnthePath) 00758 SBPL_PRINTF(" * "); 00759 else 00760 SBPL_PRINTF(" ? "); 00761 } 00762 SBPL_PRINTF("\n"); 00763 } 00764 if(bPrint) SBPL_PRINTF("System Pause (return=%d)\n",system("pause")); 00765 00766 00767 //move along the path 00768 if(bPlanExists && (int)solution_stateIDs_V.size() > 1){ 00769 //get coord of the successor 00770 int newx, newy; 00771 environment_nav2D.GetCoordFromState(solution_stateIDs_V[1], newx, newy); 00772 00773 if(trueenvironment_nav2D.GetMapCost(newx,newy) >= obsthresh) 00774 { 00775 SBPL_ERROR("ERROR: robot is commanded to move into an obstacle\n"); 00776 throw new SBPL_Exception(); 00777 } 00778 00779 //move 00780 SBPL_PRINTF("moving from %d %d to %d %d\n", startx, starty, newx, newy); 00781 startx = newx; 00782 starty = newy; 00783 00784 //update the environment 00785 environment_nav2D.SetStart(startx, starty); 00786 00787 //update the planner 00788 if(planner.set_start(solution_stateIDs_V[1]) == 0){ 00789 SBPL_ERROR("ERROR: failed to update robot pose in the planner\n"); 00790 throw new SBPL_Exception(); 00791 } 00792 } 00793 00794 } 00795 00796 //print stats 00797 SBPL_PRINTF("stats: plantimes over 1 secs=%d; over 0.5 secs=%d; over 0.1 secs=%d; over 0.05 secs=%d; below 0.05 secs=%d\n", 00798 plantime_over1secs, plantime_over0p5secs, plantime_over0p1secs, plantime_over0p05secs, plantime_below0p05secs); 00799 SBPL_FPRINTF(fSol, "stats: plantimes over 1 secs=%d; over 0.5; secs=%d; over 0.1 secs=%d; over 0.05 secs=%d; below 0.05 secs=%d\n", 00800 plantime_over1secs, plantime_over0p5secs, plantime_over0p1secs, plantime_over0p05secs, plantime_below0p05secs); 00801 00802 SBPL_FFLUSH(NULL); 00803 SBPL_FCLOSE(fSol); 00804 00805 00806 return 1; 00807 } 00808 00809 00810 00811 00812 int planandnavigatexythetalat(int argc, char *argv[]) 00813 { 00814 00815 double allocated_time_secs_foreachplan = 3.0; //in seconds 00816 MDPConfig MDPCfg; 00817 EnvironmentNAVXYTHETALAT environment_navxythetalat; 00818 EnvironmentNAVXYTHETALAT trueenvironment_navxythetalat; 00819 int size_x=-1,size_y=-1; 00820 double startx = 0, starty = 0, starttheta = 0; 00821 double goalx=-1, goaly=-1, goaltheta = -1; 00822 double goaltol_x = 0.001, goaltol_y = 0.001, goaltol_theta = 0.001; 00823 #ifndef ROS 00824 const char* sol = "sol.txt"; 00825 #endif 00826 FILE* fSol = SBPL_FOPEN(sol, "w"); 00827 if(fSol == NULL){ 00828 SBPL_ERROR("ERROR: could not open solution file\n"); 00829 throw new SBPL_Exception(); 00830 } 00831 //int dx[8] = {-1, -1, -1, 0, 0, 1, 1, 1}; 00832 //int dy[8] = {-1, 0, 1, -1, 1, -1, 0, 1}; 00833 bool bPrint = true, bPrintMap = false; 00834 int x,y; 00835 vector<int> preds_of_changededgesIDV; 00836 vector<nav2dcell_t> changedcellsV; 00837 nav2dcell_t nav2dcell; 00838 int i; 00839 double cellsize_m, nominalvel_mpersecs, timetoturn45degsinplace_secs; 00840 bool bsearchuntilfirstsolution = false; 00841 unsigned char obsthresh = 0; 00842 unsigned char costinscribed_thresh = 0; 00843 unsigned char costcircum_thresh = 0; 00844 char sMotPrimFilename[1024]; 00845 char* pMotPrimFilename = NULL; 00846 00847 //get the name of motion primitives file 00848 if(argc > 2) 00849 { 00850 strcpy(sMotPrimFilename, argv[2]); 00851 pMotPrimFilename = sMotPrimFilename; 00852 SBPL_PRINTF("using motion primitive file %s\n", pMotPrimFilename); 00853 } 00854 else 00855 { 00856 pMotPrimFilename = NULL; 00857 SBPL_PRINTF("no motion primitives file provided\n"); 00858 } 00859 00860 //srand(0); 00861 00862 //initialize true map and robot map 00863 if(!trueenvironment_navxythetalat.InitializeEnv(argv[1])) 00864 { 00865 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00866 throw new SBPL_Exception(); 00867 } 00868 00869 //get environment parameters 00870 vector<SBPL_xytheta_mprimitive> motionprimitiveV; 00871 trueenvironment_navxythetalat.GetEnvParms(&size_x, &size_y, &startx, &starty, &starttheta, &goalx, &goaly, &goaltheta, &cellsize_m, 00872 &nominalvel_mpersecs, &timetoturn45degsinplace_secs, &obsthresh, &motionprimitiveV); 00873 costinscribed_thresh = trueenvironment_navxythetalat.GetEnvParameter("cost_inscribed_thresh"); 00874 costcircum_thresh = trueenvironment_navxythetalat.GetEnvParameter("cost_possibly_circumscribed_thresh"); 00875 00876 unsigned char* map = (unsigned char*)calloc(size_x*size_y, sizeof(unsigned char)); 00877 00878 //print the map 00879 if(bPrintMap) SBPL_PRINTF("true map:\n"); 00880 for(y = 0; bPrintMap && y < size_y; y++){ 00881 for(x = 0; x < size_x; x++){ 00882 SBPL_PRINTF("%3d ", trueenvironment_navxythetalat.GetMapCost(x,y)); 00883 } 00884 SBPL_PRINTF("\n"); 00885 } 00886 if(bPrint) SBPL_PRINTF("System Pause (return=%d)\n",system("pause")); 00887 00888 SBPL_PRINTF("start: %f %f %f, goal: %f %f %f\n", startx, starty, starttheta, goalx, goaly, goaltheta); 00889 00890 //set the perimeter of the robot (it is given with 0,0,0 robot ref. point for which planning is done) 00891 vector<sbpl_2Dpt_t> perimeterptsV; 00892 sbpl_2Dpt_t pt_m; 00893 double halfwidth = 0.025; //0.3; 00894 double halflength = 0.025; //0.45; 00895 pt_m.x = -halflength; 00896 pt_m.y = -halfwidth; 00897 perimeterptsV.push_back(pt_m); 00898 pt_m.x = halflength; 00899 pt_m.y = -halfwidth; 00900 perimeterptsV.push_back(pt_m); 00901 pt_m.x = halflength; 00902 pt_m.y = halfwidth; 00903 perimeterptsV.push_back(pt_m); 00904 pt_m.x = -halflength; 00905 pt_m.y = halfwidth; 00906 perimeterptsV.push_back(pt_m); 00907 00908 //compute sensing 00909 double maxx = 0; 00910 double maxy = 0; 00911 for(i = 0; i < (int)perimeterptsV.size(); i++) 00912 { 00913 if(maxx < fabs(perimeterptsV.at(i).x)) 00914 maxx = fabs(perimeterptsV.at(i).x); 00915 if(maxy < fabs(perimeterptsV.at(i).y)) 00916 maxy = fabs(perimeterptsV.at(i).y); 00917 } 00918 //TODO - when running it, no obstacle show up when it is 20 and not 2 - bug 00919 int sensingrange_c = (int)(__max(maxx, maxy)/cellsize_m) + 2; //should be big enough to cover the motion primitive length 00920 SBPL_PRINTF("sensing range=%d cells\n", sensingrange_c); 00921 vector<sbpl_2Dcell_t> sensecells; 00922 for(i = -sensingrange_c; i <= sensingrange_c; i++) 00923 { 00924 sbpl_2Dcell_t sensecell; 00925 00926 sensecell.x = i; 00927 sensecell.y = sensingrange_c; 00928 sensecells.push_back(sensecell); 00929 sensecell.x = i; 00930 sensecell.y = -sensingrange_c; 00931 sensecells.push_back(sensecell); 00932 sensecell.x = sensingrange_c; 00933 sensecell.y = i; 00934 sensecells.push_back(sensecell); 00935 sensecell.x = -sensingrange_c; 00936 sensecell.y = i; 00937 sensecells.push_back(sensecell); 00938 } 00939 00940 00941 //Set environment parameters (should be done before initialize function is called) 00942 //set parameters - should be done before initialization 00943 if(!environment_navxythetalat.SetEnvParameter("cost_inscribed_thresh", costinscribed_thresh)) 00944 { 00945 SBPL_ERROR("ERROR: failed to set parameters\n"); 00946 throw new SBPL_Exception(); 00947 } 00948 if(!environment_navxythetalat.SetEnvParameter("cost_possibly_circumscribed_thresh", costcircum_thresh)) 00949 { 00950 SBPL_ERROR("ERROR: failed to set parameters\n"); 00951 throw new SBPL_Exception(); 00952 } 00953 00954 //Initialize Environment (should be called before initializing anything else) 00955 if(!environment_navxythetalat.InitializeEnv(size_x, size_y, 0, 0,0,0,0,0,0, 00956 goaltol_x, goaltol_y, goaltol_theta, perimeterptsV, 00957 cellsize_m, nominalvel_mpersecs, timetoturn45degsinplace_secs, 00958 obsthresh, pMotPrimFilename)){ 00959 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00960 throw new SBPL_Exception(); 00961 } 00962 00963 /* 00964 if(!environment_navxythetalat.InitializeEnv(size_x, size_y, map, startx, starty, starttheta, goalx, goaly, goaltheta, 00965 goaltol_x, goaltol_y, goaltol_theta, perimeterptsV, 00966 cellsize_m, nominalvel_mpersecs, timetoturn45degsinplace_secs, 00967 obsthresh)){ 00968 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 00969 throw new SBPL_Exception(); 00970 } 00971 */ 00972 //set start state 00973 environment_navxythetalat.SetStart(startx, starty,starttheta); 00974 00975 //Initialize MDP Info 00976 if(!environment_navxythetalat.InitializeMDPCfg(&MDPCfg)) 00977 { 00978 SBPL_ERROR("ERROR: InitializeMDPCfg failed\n"); 00979 throw new SBPL_Exception(); 00980 } 00981 00982 00983 //create a planner 00984 vector<int> solution_stateIDs_V; 00985 bool bforwardsearch = false; 00986 //ARAPlanner planner(&environment_navxythetalat, bforwardsearch); 00987 ADPlanner planner(&environment_navxythetalat, bforwardsearch); 00988 00989 planner.set_initialsolution_eps(3.0); 00990 00991 //set search mode 00992 planner.set_search_mode(bsearchuntilfirstsolution); 00993 00994 //set the start and goal configurations 00995 if(planner.set_start(MDPCfg.startstateid) == 0) 00996 { 00997 SBPL_ERROR("ERROR: failed to set start state\n"); 00998 throw new SBPL_Exception(); 00999 } 01000 01001 01002 MDPCfg.goalstateid = environment_navxythetalat.SetGoal(goalx, goaly, goaltheta); 01003 01004 01005 if(planner.set_goal(MDPCfg.goalstateid) == 0) 01006 { 01007 SBPL_ERROR("ERROR: failed to set goal state\n"); 01008 throw new SBPL_Exception(); 01009 } 01010 01011 //now comes the main loop 01012 int goalx_c = CONTXY2DISC(goalx, cellsize_m); 01013 int goaly_c = CONTXY2DISC(goaly, cellsize_m); 01014 int goaltheta_c = ContTheta2Disc(goaltheta, NAVXYTHETALAT_THETADIRS); 01015 SBPL_PRINTF("goal_c: %d %d %d\n", goalx_c, goaly_c, goaltheta_c); 01016 vector<EnvNAVXYTHETALAT3Dpt_t> xythetaPath; 01017 while(fabs(startx - goalx) > goaltol_x || fabs(starty - goaly) > goaltol_y || fabs(starttheta - goaltheta) > goaltol_theta){ 01018 01019 //simulate sensor data update 01020 bool bChanges = false; 01021 preds_of_changededgesIDV.clear(); 01022 changedcellsV.clear(); 01023 for(i = 0; i < (int)sensecells.size(); i++){ 01024 int x = CONTXY2DISC(startx,cellsize_m) + sensecells.at(i).x; 01025 int y = CONTXY2DISC(starty,cellsize_m) + sensecells.at(i).y; 01026 if(x < 0 || x >= size_x || y < 0 || y >= size_y) 01027 continue; 01028 int index = x + y*size_x; 01029 unsigned char truecost = trueenvironment_navxythetalat.GetMapCost(x,y); 01030 if(map[index] != truecost){ 01031 map[index] = truecost; 01032 environment_navxythetalat.UpdateCost(x,y,map[index]); 01033 SBPL_PRINTF("setting cost[%d][%d] to %d\n", x,y,map[index]); 01034 bChanges = true; 01035 //store the changed cells 01036 nav2dcell.x = x; 01037 nav2dcell.y = y; 01038 changedcellsV.push_back(nav2dcell); 01039 } 01040 } 01041 01042 double TimeStarted = clock(); 01043 01044 if(bChanges){ 01045 //planner.costs_changed(); //use by ARA* planner (non-incremental) 01046 01047 //get the affected states 01048 environment_navxythetalat.GetPredsofChangedEdges(&changedcellsV, &preds_of_changededgesIDV); 01049 //let know the incremental planner about them 01050 planner.update_preds_of_changededges(&preds_of_changededgesIDV); //use by AD* planner (incremental) 01051 //SBPL_PRINTF("%d states were affected\n", preds_of_changededgesIDV.size()); 01052 01053 } 01054 01055 int startx_c = CONTXY2DISC(startx,cellsize_m); 01056 int starty_c = CONTXY2DISC(starty,cellsize_m); 01057 int starttheta_c = ContTheta2Disc(starttheta, NAVXYTHETALAT_THETADIRS); 01058 01059 //plan a path 01060 bool bPlanExists = false; 01061 01062 SBPL_PRINTF("new planning...\n"); 01063 bPlanExists = (planner.replan(allocated_time_secs_foreachplan, &solution_stateIDs_V) == 1); 01064 SBPL_PRINTF("done with the solution of size=%d and sol. eps=%f\n", (unsigned int)solution_stateIDs_V.size(), planner.get_solution_eps()); 01065 environment_navxythetalat.PrintTimeStat(stdout); 01066 01067 SBPL_FPRINTF(fSol, "plan time=%.5f eps=%.2f\n", (clock()-TimeStarted)/((double)CLOCKS_PER_SEC), planner.get_solution_eps()); 01068 SBPL_FFLUSH(fSol); 01069 01070 xythetaPath.clear(); 01071 environment_navxythetalat.ConvertStateIDPathintoXYThetaPath(&solution_stateIDs_V, &xythetaPath); 01072 SBPL_PRINTF("actual path (with intermediate poses) size=%d\n", (unsigned int)xythetaPath.size()); 01073 for(unsigned int i = 0; i < xythetaPath.size(); i++) { 01074 SBPL_FPRINTF(fSol, "%.3f %.3f %.3f\n", xythetaPath.at(i).x, xythetaPath.at(i).y, xythetaPath.at(i).theta); 01075 } 01076 SBPL_FPRINTF(fSol, "*********\n"); 01077 01078 for(int j = 1; j < (int)solution_stateIDs_V.size(); j++) 01079 { 01080 int newx, newy, newtheta=0; 01081 environment_navxythetalat.GetCoordFromState(solution_stateIDs_V[j], newx, newy, newtheta); 01082 SBPL_FPRINTF(fSol, "%d %d %d\n", newx, newy, newtheta); 01083 } 01084 SBPL_FFLUSH(fSol); 01085 01086 01087 //print the map 01088 int startindex = startx_c + starty_c*size_x; 01089 int goalindex = goalx_c + goaly_c*size_x; 01090 for(y = 0; bPrintMap && y < size_y; y++){ 01091 for(x = 0; x < size_x; x++){ 01092 int index = x + y*size_x; 01093 01094 //check to see if it is on the path 01095 bool bOnthePath = false; 01096 for(int j = 1; j < (int)solution_stateIDs_V.size(); j++) 01097 { 01098 int newx, newy, newtheta=0; 01099 environment_navxythetalat.GetCoordFromState(solution_stateIDs_V[j], newx, newy, newtheta); 01100 if(x == newx && y == newy) 01101 bOnthePath = true; 01102 } 01103 01104 if (index != startindex && index != goalindex && !bOnthePath) 01105 SBPL_PRINTF("%3d ", map[index]); 01106 else if(index == startindex) 01107 SBPL_PRINTF(" X "); 01108 else if(index == goalindex) 01109 SBPL_PRINTF(" G "); 01110 else if (bOnthePath) 01111 SBPL_PRINTF(" * "); 01112 else 01113 SBPL_PRINTF("? "); 01114 } 01115 SBPL_PRINTF("\n"); 01116 } 01117 01118 //move along the path 01119 if(bPlanExists && (int) xythetaPath.size() > 1){ 01120 //get coord of the successor 01121 int newx, newy, newtheta; 01122 01123 //move until we move into the end of motion primitive 01124 environment_navxythetalat.GetCoordFromState(solution_stateIDs_V[1], newx, newy, newtheta); 01125 01126 SBPL_PRINTF("moving from %d %d %d to %d %d %d\n", startx_c, starty_c, starttheta_c, newx, newy, newtheta); 01127 01128 //this check is weak since true configuration does not know the actual perimeter of the robot 01129 if(!trueenvironment_navxythetalat.IsValidConfiguration(newx,newy,newtheta)) 01130 { 01131 SBPL_ERROR("ERROR: robot is commanded to move into an invalid configuration according to true environment\n"); 01132 throw new SBPL_Exception(); 01133 } 01134 if(!trueenvironment_navxythetalat.IsValidConfiguration(newx,newy,newtheta)) 01135 { 01136 SBPL_ERROR("ERROR: robot is commanded to move into an invalid configuration\n"); 01137 throw new SBPL_Exception(); 01138 } 01139 01140 //move 01141 startx = DISCXY2CONT(newx, cellsize_m); 01142 starty = DISCXY2CONT(newy, cellsize_m); 01143 starttheta = DiscTheta2Cont(newtheta, NAVXYTHETALAT_THETADIRS); 01144 01145 //update the environment 01146 int newstartstateID = environment_navxythetalat.SetStart(startx, starty,starttheta); 01147 01148 //update the planner 01149 if(planner.set_start(newstartstateID) == 0){ 01150 SBPL_ERROR("ERROR: failed to update robot pose in the planner\n"); 01151 throw new SBPL_Exception(); 01152 } 01153 } 01154 else 01155 { 01156 SBPL_PRINTF("No move is made\n"); 01157 } 01158 01159 if(bPrint) SBPL_PRINTF("System Pause (return=%d)\n",system("pause")); 01160 01161 01162 } 01163 01164 SBPL_PRINTF("goal reached!\n"); 01165 01166 SBPL_FFLUSH(NULL); 01167 SBPL_FCLOSE(fSol); 01168 01169 01170 return 1; 01171 } 01172 01173 01174 int planrobarm(int argc, char *argv[]) 01175 { 01176 01177 int bRet = 0; 01178 double allocated_time_secs = 5.0; //in seconds 01179 MDPConfig MDPCfg; 01180 01181 //Initialize Environment (should be called before initializing anything else) 01182 EnvironmentROBARM environment_robarm; 01183 if(!environment_robarm.InitializeEnv(argv[1])) 01184 { 01185 SBPL_ERROR("ERROR: InitializeEnv failed\n"); 01186 throw new SBPL_Exception(); 01187 } 01188 01189 //Initialize MDP Info 01190 if(!environment_robarm.InitializeMDPCfg(&MDPCfg)) 01191 { 01192 SBPL_ERROR("ERROR: InitializeMDPCfg failed\n"); 01193 throw new SBPL_Exception(); 01194 } 01195 01196 //srand(1); //TODO 01197 01198 //plan a path 01199 vector<int> solution_stateIDs_V; 01200 bool bforwardsearch = true; 01201 //ARAPlanner planner(&environment_robarm, bforwardsearch); 01202 RSTARPlanner planner(&environment_robarm, bforwardsearch); 01203 01204 if(planner.set_start(MDPCfg.startstateid) == 0) 01205 { 01206 SBPL_ERROR("ERROR: failed to set start state\n"); 01207 throw new SBPL_Exception(); 01208 } 01209 01210 if(planner.set_goal(MDPCfg.goalstateid) == 0) 01211 { 01212 SBPL_ERROR("ERROR: failed to set goal state\n"); 01213 throw new SBPL_Exception(); 01214 } 01215 01216 SBPL_PRINTF("start planning...\n"); 01217 bRet = planner.replan(allocated_time_secs, &solution_stateIDs_V); 01218 SBPL_PRINTF("done planning\n"); 01219 std::cout << "size of solution=" << solution_stateIDs_V.size() << std::endl; 01220 01221 #ifndef ROS 01222 const char* sol = "sol.txt"; 01223 #endif 01224 FILE* fSol = SBPL_FOPEN(sol, "w"); 01225 if(fSol == NULL){ 01226 SBPL_ERROR("ERROR: could not open solution file\n"); 01227 throw new SBPL_Exception(); 01228 } 01229 for(unsigned int i = 0; i < solution_stateIDs_V.size(); i++) { 01230 environment_robarm.PrintState(solution_stateIDs_V[i], true, fSol); 01231 } 01232 SBPL_FCLOSE(fSol); 01233 01234 01235 //print a path 01236 if(bRet) 01237 { 01238 //print the solution 01239 SBPL_PRINTF("Solution is found\n"); 01240 } 01241 else 01242 SBPL_PRINTF("Solution does not exist\n"); 01243 01244 SBPL_FFLUSH(NULL); 01245 01246 01247 return bRet; 01248 } 01249 01250 01251 01252 01253 01254 01255 int main(int argc, char *argv[]) 01256 { 01257 #ifdef ROS 01258 ros::init(argc, argv, "sbpl_test"); 01259 #endif 01260 01261 if(argc < 2) 01262 { 01263 PrintUsage(argv); 01264 throw new SBPL_Exception(); 01265 } 01266 01267 //2D planning 01268 //usage: exename 2Denvironmentfile.cfg 01269 //2Denvironmentfile.cfg files can be found sbpl/env_examples/nav2d 01270 //plan2d(argc, argv); 01271 //planandnavigate2d(argc, argv); 01272 01273 //xytheta planning 01274 //usage: exename 3Denvironmentfile.cfg motionprimitivesfile.mprim 01275 //3Denvironmentfile.cfg files can be found sbpl/env_examples/nav3d 01276 //the motionprimitives files can be found in matlab/mprim directory 01277 //note: the resolution of the motion primitives files should match the resolution of the cfg files 01278 planxythetalat(argc, argv); 01279 01280 //xytheta planning 01281 //usage: see the comments for planxythetalat() above 01282 //planandnavigatexythetalat(argc, argv); 01283 01284 //xytheta with multiple levels (i.e., base of the robot and upper body) 01285 //usage: see the comments for planxythetalat() above 01286 planxythetamlevlat(argc, argv); 01287 01288 //robotarm planning 01289 //usage: exename robarmenvironmentfile.cfg 01290 //robarmenvironmentfile.cfg files can be found sbpl/env_examples/robarm 01291 //planrobarm(argc, argv); 01292 01293 //plan under uncertainty (with incomplete information to be exact) 01294 //not functional yet 01295 //plan2duu(argc, argv); //not fully implemented yet 01296 01297 return 0; 01298 } 01299 01300 01301 01302 01303