$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 //TODO - define RSTAR_DEBUG_PRINTLOWLEVELEXP and RSTAR_DEBUG_PRINTHIGHLEVELEXP. Make them dependent on DEBUG 00036 //use them to print expands into two separate file. 00037 00038 //----------------------------------------------------------------------------------------------------- 00039 00040 RSTARPlanner::RSTARPlanner(DiscreteSpaceInformation* environment, bool bSearchForward) 00041 { 00042 bforwardsearch = bSearchForward; 00043 00044 environment_ = environment; 00045 00046 bsearchuntilfirstsolution = false; 00047 finitial_eps = RSTAR_DEFAULT_INITIAL_EPS; 00048 highlevel_searchexpands = 0; 00049 lowlevel_searchexpands = 0; 00050 MaxMemoryCounter = 0; 00051 00052 #ifndef ROS 00053 const char* debug = "debug.txt"; 00054 #endif 00055 fDeb = SBPL_FOPEN(debug, "w"); 00056 if(fDeb == NULL){ 00057 SBPL_ERROR("ERROR: could not open planner debug file\n"); 00058 throw new SBPL_Exception(); 00059 } 00060 SBPL_PRINTF("debug on\n"); 00061 00062 //create global searchstatespace 00063 pSearchStateSpace = new RSTARSearchStateSpace_t; 00064 MaxMemoryCounter += sizeof(RSTARSearchStateSpace_t); 00065 00066 //create local searchstatespace 00067 pLSearchStateSpace = new RSTARLSearchStateSpace_t; 00068 MaxMemoryCounter += sizeof(RSTARLSearchStateSpace_t); 00069 00070 00071 00072 //create the RSTAR planner 00073 if(CreateSearchStateSpace() != 1) 00074 { 00075 SBPL_ERROR("ERROR: failed to create statespace\n"); 00076 return; 00077 } 00078 00079 //set the start and goal states 00080 if(InitializeSearchStateSpace() != 1) 00081 { 00082 SBPL_ERROR("ERROR: failed to create statespace\n"); 00083 return; 00084 } 00085 } 00086 00087 RSTARPlanner::~RSTARPlanner() 00088 { 00089 if(pSearchStateSpace != NULL){ 00090 //delete the statespace 00091 DeleteSearchStateSpace(); 00092 delete pSearchStateSpace; 00093 } 00094 SBPL_FCLOSE(fDeb); 00095 } 00096 00097 00098 void RSTARPlanner::Initialize_searchinfo(CMDPSTATE* state) 00099 { 00100 00101 RSTARState* searchstateinfo = (RSTARState*)state->PlannerSpecificData; 00102 00103 searchstateinfo->MDPstate = state; 00104 InitializeSearchStateInfo(searchstateinfo); 00105 } 00106 00107 00108 CMDPSTATE* RSTARPlanner::CreateState(int stateID) 00109 { 00110 CMDPSTATE* state = NULL; 00111 00112 #if DEBUG 00113 if(environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND] != -1) 00114 { 00115 SBPL_ERROR("ERROR in CreateState: state already created\n"); 00116 throw new SBPL_Exception(); 00117 } 00118 #endif 00119 00120 //adds to the tail a state 00121 state = pSearchStateSpace->searchMDP.AddState(stateID); 00122 00123 //remember the index of the state 00124 environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND] = pSearchStateSpace->searchMDP.StateArray.size()-1; 00125 00126 #if DEBUG 00127 if(state != pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND]]) 00128 { 00129 SBPL_ERROR("ERROR in CreateState: invalid state index\n"); 00130 throw new SBPL_Exception(); 00131 } 00132 #endif 00133 00134 00135 //create search specific info 00136 state->PlannerSpecificData = new RSTARState; 00137 MaxMemoryCounter += sizeof(RSTARState); 00138 Initialize_searchinfo(state); 00139 00140 return state; 00141 00142 } 00143 00144 CMDPSTATE* RSTARPlanner::GetState(int stateID) 00145 { 00146 00147 if(stateID >= (int)environment_->StateID2IndexMapping.size()) 00148 { 00149 SBPL_ERROR("ERROR int GetState: stateID %d is invalid\n", stateID); 00150 throw new SBPL_Exception(); 00151 } 00152 00153 if(environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND] == -1) 00154 return CreateState(stateID); 00155 else 00156 return pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][RSTARMDP_STATEID2IND]]; 00157 00158 } 00159 00160 00161 00162 //----------------------------------------------------------------------------------------------------- 00163 00164 00165 //----------------------------------------functions related to local searches--------------------------------------------- 00166 void RSTARPlanner::Initialize_rstarlsearchdata(CMDPSTATE* state) 00167 { 00168 RSTARLSearchState* rstarlsearch_data = (RSTARLSearchState*)state->PlannerSpecificData; 00169 00170 rstarlsearch_data->bestpredstate = NULL; 00171 rstarlsearch_data->bestpredstateactioncost = 0; 00172 rstarlsearch_data->iteration = 0; 00173 rstarlsearch_data->iterationclosed = 0; 00174 rstarlsearch_data->g = INFINITECOST; 00175 rstarlsearch_data->heapindex = 0; 00176 rstarlsearch_data->listelem[0] = NULL; 00177 rstarlsearch_data->listelem[1] = NULL; 00178 00179 //pointer to itself 00180 rstarlsearch_data->MDPstate = state; 00181 00182 } 00183 00184 CMDPSTATE* RSTARPlanner::CreateLSearchState(int stateID) 00185 { 00186 CMDPSTATE* state = NULL; 00187 00188 #if DEBUG 00189 if(environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND] != -1) 00190 { 00191 SBPL_ERROR("ERROR in CreateState: state already created\n"); 00192 throw new SBPL_Exception(); 00193 } 00194 #endif 00195 00196 //adds to the tail a state 00197 state = pLSearchStateSpace->MDP.AddState(stateID); 00198 00199 //remember the index of the state 00200 environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND] = pLSearchStateSpace->MDP.StateArray.size()-1; 00201 00202 #if DEBUG 00203 if(state != pLSearchStateSpace->MDP.StateArray[environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND]]) 00204 { 00205 SBPL_ERROR("ERROR in CreateState: invalid state index\n"); 00206 throw new SBPL_Exception(); 00207 } 00208 #endif 00209 00210 //create and initialize rstarlsearch_data 00211 state->PlannerSpecificData = new RSTARLSearchState; 00212 Initialize_rstarlsearchdata(state); 00213 00214 return state; 00215 00216 } 00217 00218 CMDPSTATE* RSTARPlanner::GetLSearchState(int stateID) 00219 { 00220 00221 if(stateID >= (int)environment_->StateID2IndexMapping.size()) 00222 { 00223 SBPL_ERROR("ERROR int GetLSearchState: stateID is invalid\n"); 00224 throw new SBPL_Exception(); 00225 } 00226 00227 if(environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND] == -1) 00228 return CreateLSearchState(stateID); 00229 else 00230 return pLSearchStateSpace->MDP.StateArray[environment_->StateID2IndexMapping[stateID][RSTARMDP_LSEARCH_STATEID2IND]]; 00231 00232 } 00233 00234 CKey RSTARPlanner::LocalSearchComputeKey(RSTARLSearchState* rstarlsearchState) 00235 { 00236 CKey retkey; 00237 00238 int h; 00239 if(bforwardsearch) 00240 h = environment_->GetFromToHeuristic(rstarlsearchState->MDPstate->StateID, pLSearchStateSpace->GoalState->StateID); 00241 else 00242 h = environment_->GetFromToHeuristic(pLSearchStateSpace->GoalState->StateID, rstarlsearchState->MDPstate->StateID); 00243 00244 retkey.key[0] = rstarlsearchState->g + (int)(pSearchStateSpace->eps*h); 00245 00246 return retkey; 00247 } 00248 00249 00250 bool RSTARPlanner::ComputeLocalPath(int StartStateID, int GoalStateID, int maxc, int maxe, 00251 int *pCost, int *pCostLow, int *pExp, vector<int>* pPathIDs, int* pNewGoalStateID, double maxnumofsecs) 00252 { 00253 vector<int> SuccIDV; 00254 vector<int> CostV; 00255 00256 if(pLSearchStateSpace->OPEN == NULL) 00257 pLSearchStateSpace->OPEN = new CHeap; 00258 if(pLSearchStateSpace->INCONS == NULL) 00259 pLSearchStateSpace->INCONS = new CList; 00260 00261 int local_expands = 0; 00262 *pNewGoalStateID = GoalStateID; 00263 00264 //increase iteration 00265 pLSearchStateSpace->iteration++; 00266 00267 //set the start and goal states 00268 pLSearchStateSpace->StartState = GetLSearchState(StartStateID); 00269 pLSearchStateSpace->GoalState = GetLSearchState(GoalStateID); 00270 00271 RSTARLSearchState* rstarlsearchstate = (RSTARLSearchState*)pLSearchStateSpace->StartState->PlannerSpecificData; 00272 RSTARLSearchState* rstarlsearchgoalstate = (RSTARLSearchState*)pLSearchStateSpace->GoalState->PlannerSpecificData; 00273 00274 //OPEN=0 (it shouldn't be necessary since the memory is cleared before each search) 00275 pLSearchStateSpace->OPEN->makeemptyheap(); 00276 pLSearchStateSpace->INCONS->makeemptylist(RSTAR_INCONS_LIST_ID); 00277 00278 //CLOSED = 0 because iteration is increased 00279 00280 //g(start) = 0 00281 rstarlsearchstate->g = 0; 00282 00283 //insert start into open 00284 pLSearchStateSpace->OPEN->insertheap(rstarlsearchstate, LocalSearchComputeKey(rstarlsearchstate)); 00285 00286 //TODO - prove that min_{OPEN and INCONS} (g + eps*h) <= eps*c*. (proof: take min_{OPEN and INCONS} (g+h) <= c* and 00287 //multiply both sides by eps and then bring eps into min and drop one by g. I still need to implement INCONS and minimum tracker for it - then change 00288 //the minkey to min over two sets 00289 while(rstarlsearchgoalstate->g > pLSearchStateSpace->OPEN->getminkeyheap().key[0] && local_expands < maxe && 00290 pLSearchStateSpace->OPEN->getminkeyheap().key[0] <= maxc) 00291 { 00292 //pop the min element 00293 rstarlsearchstate = (RSTARLSearchState*)pLSearchStateSpace->OPEN->deleteminheap(); 00294 00295 //close the state 00296 rstarlsearchstate->iterationclosed = pLSearchStateSpace->iteration; 00297 00298 //expansion 00299 local_expands++; 00300 //environment_->PrintState(rstarlsearchstate->MDPstate->StateID, false, fLowLevelExp); 00301 00302 //generate SUCCS state 00303 SuccIDV.clear(); 00304 CostV.clear(); 00305 //this setting makes it to get all successors - since this is a deterministic search 00306 if(bforwardsearch == false) 00307 environment_->GetPreds(rstarlsearchstate->MDPstate->StateID, &SuccIDV, &CostV); 00308 else 00309 environment_->GetSuccs(rstarlsearchstate->MDPstate->StateID, &SuccIDV, &CostV); 00310 00311 //iterate over states in SUCCS set 00312 for(int i = 0; i < (int)SuccIDV.size(); i++) 00313 { 00314 RSTARLSearchState* rstarlsearchSuccState = (RSTARLSearchState*)GetLSearchState(SuccIDV.at(i))->PlannerSpecificData; 00315 00316 //skip if the state is already closed - TODO fix this with INCONS list - it seems to make five times less expansions! 00317 //if(rstarlsearchSuccState->iterationclosed == pLSearchStateSpace->iteration) 00318 //continue; 00319 00320 //see if we can improve g-value of successor 00321 if(rstarlsearchstate->g + CostV[i] < rstarlsearchSuccState->g) 00322 { 00323 rstarlsearchSuccState->bestpredstate = rstarlsearchstate->MDPstate; 00324 rstarlsearchSuccState->bestpredstateactioncost = CostV[i]; 00325 rstarlsearchSuccState->g = rstarlsearchstate->g + CostV[i]; 00326 if(rstarlsearchSuccState->heapindex == 0) 00327 pLSearchStateSpace->OPEN->insertheap(rstarlsearchSuccState, LocalSearchComputeKey(rstarlsearchSuccState)); 00328 else 00329 pLSearchStateSpace->OPEN->updateheap(rstarlsearchSuccState, LocalSearchComputeKey(rstarlsearchSuccState)); 00330 00331 00332 if(environment_->AreEquivalent(rstarlsearchSuccState->MDPstate->StateID, rstarlsearchgoalstate->MDPstate->StateID) == true && rstarlsearchSuccState->g < rstarlsearchgoalstate->g) 00333 { 00334 //swap the goal 00335 rstarlsearchgoalstate = rstarlsearchSuccState; 00336 GoalStateID = rstarlsearchgoalstate->MDPstate->StateID; 00337 } 00338 } 00339 } 00340 00341 if(local_expands%10000 == 0) 00342 { 00343 if((clock()-TimeStarted) >= maxnumofsecs*(double)CLOCKS_PER_SEC) 00344 { 00345 SBPL_PRINTF("breaking local search because global planning time expires\n"); 00346 break; 00347 } 00348 } 00349 00350 00351 }//while 00352 00353 lowlevel_searchexpands += local_expands; 00354 SBPL_FPRINTF(fDeb, "local search: expands=%d\n", local_expands); 00355 00356 //set the return path and other path related variables 00357 vector<int> tempPathID; 00358 pPathIDs->clear(); 00359 if(rstarlsearchgoalstate->g < INFINITECOST) 00360 { 00361 int pathcost = 0; 00362 00363 //path exists 00364 rstarlsearchstate = rstarlsearchgoalstate; 00365 while(rstarlsearchstate->bestpredstate != NULL && rstarlsearchstate->MDPstate != pLSearchStateSpace->StartState) 00366 { 00367 tempPathID.push_back(rstarlsearchstate->MDPstate->StateID); 00368 pathcost += rstarlsearchstate->bestpredstateactioncost; 00369 rstarlsearchstate = (RSTARLSearchState*)rstarlsearchstate->bestpredstate->PlannerSpecificData; 00370 } 00371 //store into pPathIDs so that the path is always forward path w.r.t. the original graph 00372 //this requires us to reverse order in case of forward search 00373 for(int i = 0; i < (int)tempPathID.size(); i++) 00374 { 00375 if(bforwardsearch == false) 00376 pPathIDs->push_back(tempPathID.at(i)); 00377 else 00378 pPathIDs->push_back(tempPathID.at(tempPathID.size() - i - 1)); 00379 } 00380 *pCost = pathcost; 00381 *pCostLow = rstarlsearchgoalstate->g; 00382 SBPL_FPRINTF(fDeb, "pathcost=%d while g=%d\n", pathcost, rstarlsearchgoalstate->g); 00383 } 00384 else 00385 { 00386 *pCost = INFINITECOST; 00387 *pCostLow = pLSearchStateSpace->OPEN->getminkeyheap().key[0]; 00388 if(*pCostLow != pLSearchStateSpace->OPEN->getminkeyheap().key[0]){ 00389 SBPL_FPRINTF(fDeb, "after localsearch clow=%d while keymin=%d\n", (int)(*pCostLow), 00390 (int)pLSearchStateSpace->OPEN->getminkeyheap().key[0]); 00391 } 00392 } 00393 00394 //set all other return variables 00395 *pExp = local_expands; 00396 *pNewGoalStateID = GoalStateID; 00397 00398 return true; 00399 00400 } 00401 00402 bool RSTARPlanner::DestroyLocalSearchMemory() 00403 { 00404 pLSearchStateSpace->OPEN->currentsize = 0; 00405 pLSearchStateSpace->StartState = pLSearchStateSpace->GoalState = NULL; 00406 00407 //remove the states in the MDP itself 00408 for(int i = 0; i < (int)pLSearchStateSpace->MDP.StateArray.size(); i++) 00409 { 00410 CMDPSTATE* state = pLSearchStateSpace->MDP.StateArray.at(i); 00411 RSTARLSearchState* rstarlsearchstatedata = (RSTARLSearchState*)state->PlannerSpecificData; 00412 delete rstarlsearchstatedata; 00413 state->PlannerSpecificData = NULL; 00414 environment_->StateID2IndexMapping[state->StateID][RSTARMDP_LSEARCH_STATEID2IND] = -1; 00415 } 00416 //now we can delete the states themselves 00417 if(pLSearchStateSpace->MDP.Delete() == false) 00418 { 00419 SBPL_ERROR("ERROR: failed to delete local search MDP\n"); 00420 throw new SBPL_Exception(); 00421 } 00422 00423 //TODO - ask Env to delete the new memory allocated during the local search (usings the fact that stateID's for local search continuously and no states were 00424 //allocated for global search before local search exits. 00425 00426 return true; 00427 } 00428 00429 00430 00431 //---------------------------------------------------------------------------------------------------------------------- 00432 00433 00434 00435 int RSTARPlanner::ComputeHeuristic(CMDPSTATE* MDPstate) 00436 { 00437 //compute heuristic for search 00438 00439 if(pSearchStateSpace->searchgoalstate == NULL) 00440 return 0; //the heuristics will be re-computed anyway when searchgoalstate is updated 00441 00442 if(bforwardsearch) 00443 { 00444 00445 #if MEM_CHECK == 1 00446 //int WasEn = DisableMemCheck(); 00447 #endif 00448 00449 //forward search: heur = distance from state to searchgoal which is Goal RSTARState 00450 int retv = environment_->GetFromToHeuristic(MDPstate->StateID, pSearchStateSpace->searchgoalstate->StateID); 00451 00452 #if MEM_CHECK == 1 00453 //if (WasEn) 00454 // EnableMemCheck(); 00455 #endif 00456 00457 return retv; 00458 00459 } 00460 else 00461 { 00462 //backward search: heur = distance from searchgoal to state 00463 return environment_->GetFromToHeuristic(pSearchStateSpace->searchgoalstate->StateID, MDPstate->StateID); 00464 } 00465 } 00466 00467 00468 //initialization of a state 00469 void RSTARPlanner::InitializeSearchStateInfo(RSTARState* state) 00470 { 00471 state->g = INFINITECOST; 00472 state->iterationclosed = 0; 00473 state->callnumberaccessed = pSearchStateSpace->callnumber; 00474 state->heapindex = 0; 00475 state->bestpredaction = NULL; 00476 00477 //compute heuristics 00478 #if USE_HEUR 00479 if(pSearchStateSpace->searchgoalstate != NULL) 00480 state->h = ComputeHeuristic(state->MDPstate); 00481 else 00482 state->h = 0; 00483 #else 00484 state->h = 0; 00485 #endif 00486 00487 state->predactionV.clear(); 00488 00489 } 00490 00491 00492 00493 //re-initialization of a state 00494 void RSTARPlanner::ReInitializeSearchStateInfo(RSTARState* state) 00495 { 00496 state->g = INFINITECOST; 00497 state->iterationclosed = 0; 00498 state->callnumberaccessed = pSearchStateSpace->callnumber; 00499 state->heapindex = 0; 00500 00501 state->bestpredaction = NULL; 00502 00503 //compute heuristics 00504 #if USE_HEUR 00505 00506 if(pSearchStateSpace->searchgoalstate != NULL) 00507 { 00508 state->h = ComputeHeuristic(state->MDPstate); 00509 } 00510 else 00511 state->h = 0; 00512 00513 #else 00514 00515 state->h = 0; 00516 00517 #endif 00518 00519 state->predactionV.clear(); 00520 for(int i = 0; i < (int)state->MDPstate->Actions.size(); i++){ 00521 if(state->MDPstate->Actions.at(i)->PlannerSpecificData != NULL){ 00522 DeleteSearchActionData((RSTARACTIONDATA*)state->MDPstate->Actions.at(i)->PlannerSpecificData); 00523 delete (RSTARACTIONDATA*)(state->MDPstate->Actions.at(i)->PlannerSpecificData); 00524 state->MDPstate->Actions.at(i)->PlannerSpecificData = NULL; 00525 } 00526 } 00527 state->MDPstate->RemoveAllActions(); 00528 00529 } 00530 00531 00532 00533 void RSTARPlanner::DeleteSearchStateData(RSTARState* state) 00534 { 00535 //delete PlannerSpecificData for each action 00536 state->predactionV.clear(); 00537 for(int i = 0; i < (int)state->MDPstate->Actions.size(); i++){ 00538 if(state->MDPstate->Actions.at(i)->PlannerSpecificData != NULL){ 00539 DeleteSearchActionData((RSTARACTIONDATA*)state->MDPstate->Actions.at(i)->PlannerSpecificData); 00540 delete (RSTARACTIONDATA*)state->MDPstate->Actions.at(i)->PlannerSpecificData; 00541 state->MDPstate->Actions.at(i)->PlannerSpecificData = NULL; 00542 } 00543 } 00544 state->MDPstate->RemoveAllActions(); 00545 00546 return; 00547 } 00548 00549 void RSTARPlanner::DeleteSearchActionData(RSTARACTIONDATA* actiondata) 00550 { 00551 //no memory was allocated for actiondata 00552 00553 return; 00554 } 00555 00556 00557 int RSTARPlanner::GetGVal(int StateID) 00558 { 00559 CMDPSTATE* cmdp_state = GetState(StateID); 00560 RSTARState* state = (RSTARState*)cmdp_state->PlannerSpecificData; 00561 return state->g; 00562 } 00563 00564 00565 void RSTARPlanner::SetBestPredecessor(RSTARState* rstarState, RSTARState* rstarPredState, CMDPACTION* action) 00566 { 00567 rstarState->bestpredaction = action; 00568 rstarState->g = rstarPredState->g + ((RSTARACTIONDATA*)(action->PlannerSpecificData))->clow; 00569 if(rstarState->heapindex == 0) 00570 pSearchStateSpace->OPEN->insertheap(rstarState, ComputeKey(rstarState)); 00571 else 00572 pSearchStateSpace->OPEN->updateheap(rstarState, ComputeKey(rstarState)); 00573 00574 } 00575 00576 CKey RSTARPlanner::ComputeKey(RSTARState* rstarState) 00577 { 00578 CKey retkey; 00579 00580 int h, starttostateh; 00581 if(bforwardsearch) 00582 { 00583 h = environment_->GetFromToHeuristic(rstarState->MDPstate->StateID, pSearchStateSpace->searchgoalstate->StateID); 00584 starttostateh = environment_->GetFromToHeuristic(pSearchStateSpace->searchstartstate->StateID, rstarState->MDPstate->StateID); 00585 } 00586 else 00587 { 00588 h = environment_->GetFromToHeuristic(pSearchStateSpace->searchgoalstate->StateID, rstarState->MDPstate->StateID); 00589 starttostateh = environment_->GetFromToHeuristic(rstarState->MDPstate->StateID, pSearchStateSpace->searchstartstate->StateID); 00590 } 00591 00592 //compute 2nd element of the key 00593 retkey.key[1] = rstarState->g + (int)(pSearchStateSpace->eps*h); 00594 00595 //compute the 1st element 00596 if(rstarState->g > pSearchStateSpace->eps*starttostateh || 00597 (rstarState->bestpredaction != NULL && ((RSTARACTIONDATA*)rstarState->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0 && 00598 ((RSTARACTIONDATA*)rstarState->bestpredaction->PlannerSpecificData)->exp >= RSTAR_EXPTHRESH)) 00599 retkey.key[0] = 1; 00600 else 00601 retkey.key[0] = 0; 00602 00603 return retkey; 00604 } 00605 00606 00607 //returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time 00608 int RSTARPlanner::ImprovePath(double MaxNumofSecs) 00609 { 00610 int expands; 00611 RSTARState *rstarstate, *searchgoalstate, *searchstartstate; 00612 CKey key, minkey; 00613 CKey goalkey; 00614 00615 vector<int> SuccIDV; 00616 vector<int> CLowV; 00617 int highlevelexpands = 0; 00618 00619 expands = 0; 00620 00621 if(pSearchStateSpace->searchgoalstate == NULL) 00622 { 00623 SBPL_ERROR("ERROR searching: no goal state is set\n"); 00624 throw new SBPL_Exception(); 00625 } 00626 00627 //goal state 00628 searchgoalstate = (RSTARState*)(pSearchStateSpace->searchgoalstate->PlannerSpecificData); 00629 if(searchgoalstate->callnumberaccessed != pSearchStateSpace->callnumber) 00630 ReInitializeSearchStateInfo(searchgoalstate); 00631 00632 //get the start state 00633 searchstartstate = (RSTARState*)(pSearchStateSpace->searchstartstate->PlannerSpecificData); 00634 00635 //set goal key 00636 if(searchgoalstate != searchstartstate){ 00637 goalkey.key[0] = 1; 00638 goalkey.key[1] = INFINITECOST; 00639 } 00640 else{ 00641 goalkey = ComputeKey(searchstartstate); 00642 } 00643 00644 00645 //expand states until done 00646 minkey = pSearchStateSpace->OPEN->getminkeyheap(); 00647 while(!pSearchStateSpace->OPEN->emptyheap() && 00648 (clock()-TimeStarted) < MaxNumofSecs*(double)CLOCKS_PER_SEC) 00649 { 00650 00651 //recompute minkey 00652 minkey = pSearchStateSpace->OPEN->getminkeyheap(); 00653 00654 //recompute goalkey if necessary 00655 goalkey = ComputeKey(searchgoalstate); 00656 00657 if(goalkey < minkey) 00658 break; //termination condition 00659 00660 00661 //pop the min element 00662 rstarstate = (RSTARState*)pSearchStateSpace->OPEN->deleteminheap(); 00663 00664 SBPL_FPRINTF(fDeb, "ComputePath: selected state %d g=%d\n", rstarstate->MDPstate->StateID, rstarstate->g); 00665 environment_->PrintState(rstarstate->MDPstate->StateID, true, fDeb); 00666 00667 if (rstarstate->MDPstate != pSearchStateSpace->searchstartstate && 00668 ((RSTARACTIONDATA*)rstarstate->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0) 00669 { 00670 SBPL_FPRINTF(fDeb, "re-compute path\n"); 00671 00672 int maxe = INFINITECOST; 00673 int maxc = INFINITECOST; 00674 00675 //predecessor 00676 RSTARState* rstarpredstate = (RSTARState*)GetState(rstarstate->bestpredaction->SourceStateID)->PlannerSpecificData; 00677 CMDPACTION* computedaction = rstarstate->bestpredaction; 00678 RSTARACTIONDATA* computedactiondata = (RSTARACTIONDATA*)computedaction->PlannerSpecificData; 00679 00680 00681 if(computedactiondata->exp < RSTAR_EXPTHRESH) 00682 { 00683 maxe = RSTAR_EXPTHRESH; 00684 } 00685 else 00686 { 00687 SBPL_PRINTF("Trying to compute hard-to-find path\n"); 00688 SBPL_FPRINTF(fDeb, "Trying to compute hard-to-find path\n"); 00689 /* TODO 00690 CKey nextkey = rstarPlanner.OPEN->getminkeyheap(); 00691 00692 if(bforwardsearch) 00693 h = environment_->GetFromToHeuristic(rstarstate->MDPstate->StateID, pSearchStateSpace->GoalState->StateID); 00694 else 00695 h = environment_->GetFromToHeuristic(pSearchStateSpace->GoalState->StateID, rstarstate->MDPstate->StateID); 00696 00697 maxc = nextkey[1] - 00698 (rstarpredstate->g + rstarPlanner.epsilon*h) + RSTAR_COSTDELTA; 00699 */ 00700 } 00701 00702 00703 SBPL_FPRINTF(fDeb, "recomputing path from bp %d to state %d with maxc=%d maxe=%d\n", 00704 rstarpredstate->MDPstate->StateID, rstarstate->MDPstate->StateID, maxc, maxe); 00705 SBPL_FPRINTF(fDeb, "bp state:\n"); 00706 environment_->PrintState(rstarpredstate->MDPstate->StateID, true, fDeb); 00707 00708 //re-compute the path 00709 int NewGoalStateID = rstarstate->MDPstate->StateID; 00710 ComputeLocalPath(rstarpredstate->MDPstate->StateID, rstarstate->MDPstate->StateID, maxc, maxe, 00711 &computedaction->Costs[0], &computedactiondata->clow, &computedactiondata->exp, &computedactiondata->pathIDs, &NewGoalStateID, MaxNumofSecs); 00712 00713 SBPL_FPRINTF(fDeb, "return values: pathcost=%d clow=%d exp=%d\n", 00714 computedaction->Costs[0], computedactiondata->clow, computedactiondata->exp); 00715 bool bSwitch = false; 00716 if(NewGoalStateID != rstarstate->MDPstate->StateID) 00717 { 00718 bSwitch = true; 00719 SBPL_FPRINTF(fDeb, "targetstate was switched from %d to %d\n", rstarstate->MDPstate->StateID, NewGoalStateID); 00720 SBPL_FPRINTF(stdout, "targetstate was switched from %d to %d\n", rstarstate->MDPstate->StateID, NewGoalStateID); 00721 environment_->PrintState(NewGoalStateID, true, fDeb); 00722 00723 RSTARState* rstarNewTargetState = (RSTARState*)GetState(NewGoalStateID)->PlannerSpecificData; 00724 00725 //re-initialize the state if necessary 00726 if(rstarNewTargetState->callnumberaccessed != pSearchStateSpace->callnumber) 00727 ReInitializeSearchStateInfo(rstarNewTargetState); 00728 00729 SBPL_FPRINTF(fDeb, "predstate.g=%d actual actioncost=%d clow=%d newtartetstate.g=%d\n", rstarpredstate->g, computedaction->Costs[0], 00730 ((RSTARACTIONDATA*)computedaction->PlannerSpecificData)->clow, rstarNewTargetState->g); 00731 00732 //add the successor to our graph 00733 CMDPACTION* action = rstarpredstate->MDPstate->AddAction(rstarpredstate->MDPstate->Actions.size()); 00734 action->AddOutcome(rstarNewTargetState->MDPstate->StateID, computedaction->Costs[0], 1.0); 00735 action->PlannerSpecificData = new RSTARACTIONDATA; 00736 MaxMemoryCounter += sizeof(RSTARACTIONDATA); 00737 ((RSTARACTIONDATA*)action->PlannerSpecificData)->clow = computedactiondata->clow; 00738 ((RSTARACTIONDATA*)action->PlannerSpecificData)->exp = computedactiondata->exp; 00739 ((RSTARACTIONDATA*)action->PlannerSpecificData)->pathIDs = computedactiondata->pathIDs; 00740 00741 //add the corresponding predaction 00742 rstarNewTargetState->predactionV.push_back(action); 00743 00744 //the action was not found to the old state 00745 computedaction->Costs[0] = INFINITECOST; 00746 if(bforwardsearch) 00747 computedactiondata->clow = environment_->GetFromToHeuristic(rstarpredstate->MDPstate->StateID, rstarstate->MDPstate->StateID); 00748 else 00749 computedactiondata->clow = environment_->GetFromToHeuristic(rstarstate->MDPstate->StateID, rstarpredstate->MDPstate->StateID); 00750 00751 computedactiondata->pathIDs.clear(); 00752 00753 rstarstate = rstarNewTargetState; 00754 computedaction = action; 00755 computedactiondata = (RSTARACTIONDATA*)action->PlannerSpecificData; 00756 } 00757 00758 //clean up local search memory 00759 DestroyLocalSearchMemory(); 00760 00761 RSTARState* stateu = NULL; 00762 CMDPACTION* utosaction = NULL; 00763 int hfromstarttostate; 00764 if(bforwardsearch) 00765 hfromstarttostate = environment_->GetFromToHeuristic(searchstartstate->MDPstate->StateID, rstarstate->MDPstate->StateID); 00766 else 00767 hfromstarttostate = environment_->GetFromToHeuristic(rstarstate->MDPstate->StateID,searchstartstate->MDPstate->StateID); 00768 if (computedactiondata->pathIDs.size() == 0 || 00769 rstarpredstate->g + computedactiondata->clow > pSearchStateSpace->eps*hfromstarttostate) 00770 { 00771 SBPL_FPRINTF(fDeb, "selecting best pred\n"); 00772 //SBPL_FPRINTF(stdout, "selecting best pred\n"); 00773 00774 //select other best predecessor 00775 unsigned int minQ = INFINITECOST; 00776 for(int i = 0; i < (int)rstarstate->predactionV.size(); i++) 00777 { 00778 CMDPACTION* predaction = rstarstate->predactionV.at(i); 00779 rstarpredstate = (RSTARState*)GetState(predaction->SourceStateID)->PlannerSpecificData; 00780 if(minQ >= rstarpredstate->g + ((RSTARACTIONDATA*)predaction->PlannerSpecificData)->clow) 00781 { 00782 minQ = rstarpredstate->g + ((RSTARACTIONDATA*)predaction->PlannerSpecificData)->clow; 00783 stateu = rstarpredstate; 00784 utosaction = predaction; 00785 } 00786 } 00787 00788 //set the predecessor 00789 SetBestPredecessor(rstarstate, stateu, utosaction); 00790 } 00791 else if(rstarpredstate->g + computedactiondata->clow < rstarstate->g || bSwitch == false) 00792 { 00793 SBPL_FPRINTF(fDeb, "keeping the same computedaction\n"); 00794 //SBPL_FPRINTF(stdout, "keeping the same best pred\n"); 00795 00796 stateu = rstarpredstate; 00797 utosaction = computedaction; 00798 00799 //set the predecessor 00800 SetBestPredecessor(rstarstate, stateu, utosaction); 00801 00802 } 00803 else 00804 { 00805 SBPL_FPRINTF(fDeb, "keeping the same bestpredaction even though switch of targetstates happened\n"); 00806 } 00807 } 00808 else 00809 { 00810 SBPL_FPRINTF(fDeb, "high-level normal expansion of state %d\n", rstarstate->MDPstate->StateID); 00811 environment_->PrintState(rstarstate->MDPstate->StateID, true, fDeb); 00812 highlevelexpands++; 00813 00814 //close the state 00815 rstarstate->iterationclosed = pSearchStateSpace->searchiteration; 00816 00817 //expansion 00818 expands++; 00819 00820 //generate SUCCS state 00821 SuccIDV.clear(); 00822 CLowV.clear(); 00823 if(bforwardsearch) 00824 environment_->GetRandomSuccsatDistance(rstarstate->MDPstate->StateID, &SuccIDV, &CLowV); 00825 else 00826 environment_->GetRandomPredsatDistance(rstarstate->MDPstate->StateID, &SuccIDV, &CLowV); 00827 00828 00829 SBPL_FPRINTF(fDeb, "%d succs were generated at random\n", (unsigned int)SuccIDV.size()); 00830 00831 //iterate over states in SUCCS set 00832 int notclosed = 0; 00833 for(int i = 0; i < (int)SuccIDV.size(); i++) 00834 { 00835 RSTARState* rstarSuccState = (RSTARState*)GetState(SuccIDV.at(i))->PlannerSpecificData; 00836 00837 SBPL_FPRINTF(fDeb, "succ %d:\n", i); 00838 environment_->PrintState(rstarSuccState->MDPstate->StateID, true, fDeb); 00839 00840 //skip if the state is already closed 00841 if(rstarSuccState->iterationclosed == pSearchStateSpace->searchiteration) 00842 { 00843 SBPL_FPRINTF(fDeb, "this succ was already closed -- skipping it\n"); 00844 continue; 00845 } 00846 notclosed++; 00847 00848 //re-initialize the state if necessary 00849 if(rstarSuccState->callnumberaccessed != pSearchStateSpace->callnumber) 00850 ReInitializeSearchStateInfo(rstarSuccState); 00851 00852 //if(rstarSuccState->MDPstate->StateID == 3838){ 00853 // SBPL_FPRINTF(fDeb, "generating state %d with g=%d bp=%d:\n", rstarSuccState->MDPstate->StateID, rstarSuccState->g, 00854 // (rstarSuccState->bestpredaction==NULL?-1:rstarSuccState->bestpredaction->SourceStateID)); 00855 // Env_PrintState(rstarSuccState->MDPstate->StateID, true, false, fDeb); 00856 //} 00857 00858 00859 //add the successor to our graph 00860 CMDPACTION* action = rstarstate->MDPstate->AddAction(i); 00861 action->AddOutcome(rstarSuccState->MDPstate->StateID, INFINITECOST, 1.0); 00862 action->PlannerSpecificData = new RSTARACTIONDATA; 00863 MaxMemoryCounter += sizeof(RSTARACTIONDATA); 00864 ((RSTARACTIONDATA*)action->PlannerSpecificData)->clow = CLowV[i]; 00865 ((RSTARACTIONDATA*)action->PlannerSpecificData)->exp = 0; 00866 ((RSTARACTIONDATA*)action->PlannerSpecificData)->pathIDs.clear(); 00867 00868 //add the corresponding predaction 00869 rstarSuccState->predactionV.push_back(action); 00870 00871 //see if we can improve g-value of successor 00872 if(rstarSuccState->bestpredaction == NULL || rstarstate->g + CLowV[i] < rstarSuccState->g) 00873 { 00874 SetBestPredecessor(rstarSuccState, rstarstate, action); 00875 SBPL_FPRINTF(fDeb, "bestpred was set for the succ (clow=%d)\n", CLowV[i]); 00876 } 00877 else 00878 { 00879 SBPL_FPRINTF(fDeb, "bestpred was NOT modified - old one is better\n"); 00880 } 00881 00882 } 00883 00884 //SBPL_PRINTF("%d successors were not closed\n", notclosed); 00885 }//else 00886 00887 00888 //recompute minkey 00889 minkey = pSearchStateSpace->OPEN->getminkeyheap(); 00890 00891 //recompute goalkey if necessary 00892 goalkey = ComputeKey(searchgoalstate); 00893 00894 if(expands%10 == 0 && expands > 0) 00895 { 00896 SBPL_PRINTF("high-level expands so far=%u\n", expands); 00897 } 00898 00899 } 00900 SBPL_PRINTF("main loop done\n"); 00901 SBPL_FPRINTF(fDeb, "main loop done\n"); 00902 00903 int retv = 1; 00904 if(searchgoalstate->g == INFINITECOST && pSearchStateSpace->OPEN->emptyheap()) 00905 { 00906 SBPL_PRINTF("solution does not exist: search exited because heap is empty\n"); 00907 retv = 0; 00908 } 00909 else if(!pSearchStateSpace->OPEN->emptyheap() && goalkey > minkey) 00910 { 00911 SBPL_PRINTF("search exited because it ran out of time\n"); 00912 retv = 2; 00913 } 00914 else if(searchgoalstate->g == INFINITECOST && !pSearchStateSpace->OPEN->emptyheap()) 00915 { 00916 SBPL_PRINTF("solution does not exist: search exited because all candidates for expansion have infinite heuristics\n"); 00917 retv = 0; 00918 } 00919 else 00920 { 00921 SBPL_PRINTF("search exited with a solution for eps=%.3f\n", pSearchStateSpace->eps); 00922 retv = 1; 00923 } 00924 00925 SBPL_FPRINTF(fDeb, "high-level expanded=%d\n", expands); 00926 00927 highlevel_searchexpands += expands; 00928 00929 return retv; 00930 } 00931 00932 00933 00934 //note this does NOT re-compute heuristics, only re-orders OPEN list based on current eps and h-vals 00935 void RSTARPlanner::Reevaluatefvals() 00936 { 00937 CKey key; 00938 int i; 00939 CHeap* pheap = pSearchStateSpace->OPEN; 00940 00941 //re-compute priorities for states in OPEN and reorder it 00942 for (i = 1; i <= pheap->currentsize; ++i) 00943 { 00944 RSTARState* state = (RSTARState*)pheap->heap[i].heapstate; 00945 pheap->heap[i].key = ComputeKey(state); 00946 } 00947 pheap->makeheap(); 00948 00949 pSearchStateSpace->bReevaluatefvals = false; 00950 } 00951 00952 00953 00954 00955 //creates (allocates memory) search state space 00956 //does not initialize search statespace 00957 int RSTARPlanner::CreateSearchStateSpace() 00958 { 00959 00960 //create a heap 00961 pSearchStateSpace->OPEN = new CHeap; 00962 MaxMemoryCounter += sizeof(CHeap); 00963 //pSearchStateSpace->inconslist = new CList; 00964 //MaxMemoryCounter += sizeof(CList); 00965 00966 pSearchStateSpace->searchgoalstate = NULL; 00967 pSearchStateSpace->searchstartstate = NULL; 00968 00969 pSearchStateSpace->bReinitializeSearchStateSpace = false; 00970 00971 return 1; 00972 } 00973 00974 //deallocates memory used by SearchStateSpace 00975 void RSTARPlanner::DeleteSearchStateSpace() 00976 { 00977 if(pSearchStateSpace->OPEN != NULL) 00978 { 00979 pSearchStateSpace->OPEN->makeemptyheap(); 00980 delete pSearchStateSpace->OPEN; 00981 pSearchStateSpace->OPEN = NULL; 00982 } 00983 00984 //if(pSearchStateSpace->inconslist != NULL) 00985 //{ 00986 // pSearchStateSpace->inconslist->makeemptylist(RSTAR_INCONS_LIST_ID); 00987 // delete pSearchStateSpace->inconslist; 00988 // pSearchStateSpace->inconslist = NULL; 00989 //} 00990 00991 //delete the states themselves 00992 int iend = (int)pSearchStateSpace->searchMDP.StateArray.size(); 00993 for(int i=0; i < iend; i++) 00994 { 00995 CMDPSTATE* state = pSearchStateSpace->searchMDP.StateArray[i]; 00996 if(state != NULL && state->PlannerSpecificData != NULL){ 00997 DeleteSearchStateData((RSTARState*)state->PlannerSpecificData); 00998 delete (RSTARState*)state->PlannerSpecificData; 00999 state->PlannerSpecificData = NULL; 01000 } 01001 if(state != NULL) 01002 { 01003 for(int aind = 0; aind < (int)state->Actions.size(); aind++) 01004 { 01005 if(state->Actions[aind]->PlannerSpecificData != NULL) 01006 { 01007 DeleteSearchActionData((RSTARACTIONDATA*)state->Actions[aind]->PlannerSpecificData); 01008 delete (RSTARACTIONDATA*)state->Actions[aind]->PlannerSpecificData; 01009 state->Actions[aind]->PlannerSpecificData = NULL; 01010 } 01011 }//over actions 01012 } 01013 } 01014 01015 pSearchStateSpace->searchMDP.Delete(); 01016 } 01017 01018 01019 01020 //reset properly search state space 01021 //needs to be done before deleting states 01022 int RSTARPlanner::ResetSearchStateSpace() 01023 { 01024 pSearchStateSpace->OPEN->makeemptyheap(); 01025 //pSearchStateSpace->inconslist->makeemptylist(RSTAR_INCONS_LIST_ID); 01026 01027 return 1; 01028 } 01029 01030 01031 //initialization before each search 01032 void RSTARPlanner::ReInitializeSearchStateSpace() 01033 { 01034 //increase callnumber 01035 pSearchStateSpace->callnumber++; 01036 01037 //reset iteration 01038 pSearchStateSpace->searchiteration = 0; 01039 pSearchStateSpace->bNewSearchIteration = true; 01040 01041 #if DEBUG 01042 SBPL_FPRINTF(fDeb, "reinitializing search state-space (new call number=%d search iter=%d)\n", 01043 pSearchStateSpace->callnumber,pSearchStateSpace->searchiteration ); 01044 #endif 01045 01046 pSearchStateSpace->OPEN->makeemptyheap(); 01047 //pSearchStateSpace->inconslist->makeemptylist(RSTAR_INCONS_LIST_ID); 01048 01049 //reset 01050 pSearchStateSpace->eps = this->finitial_eps; 01051 pSearchStateSpace->eps_satisfied = INFINITECOST; 01052 01053 //initialize start state 01054 RSTARState* startstateinfo = (RSTARState*)(pSearchStateSpace->searchstartstate->PlannerSpecificData); 01055 if(startstateinfo->callnumberaccessed != pSearchStateSpace->callnumber) 01056 ReInitializeSearchStateInfo(startstateinfo); 01057 01058 startstateinfo->g = 0; 01059 01060 01061 //insert start state into the heap 01062 pSearchStateSpace->OPEN->insertheap(startstateinfo, ComputeKey(startstateinfo)); 01063 01064 pSearchStateSpace->bReinitializeSearchStateSpace = false; 01065 pSearchStateSpace->bReevaluatefvals = false; 01066 } 01067 01068 01069 //very first initialization 01070 int RSTARPlanner::InitializeSearchStateSpace() 01071 { 01072 01073 if(pSearchStateSpace->OPEN->currentsize != 0) 01074 // || pSearchStateSpace->inconslist->currentsize != 0) 01075 { 01076 SBPL_ERROR("ERROR in InitializeSearchStateSpace: OPEN or INCONS is not empty\n"); 01077 throw new SBPL_Exception(); 01078 } 01079 01080 pSearchStateSpace->eps = this->finitial_eps; 01081 pSearchStateSpace->eps_satisfied = INFINITECOST; 01082 pSearchStateSpace->searchiteration = 0; 01083 pSearchStateSpace->bNewSearchIteration = true; 01084 pSearchStateSpace->callnumber = 0; 01085 pSearchStateSpace->bReevaluatefvals = false; 01086 01087 01088 //create and set the search start state 01089 pSearchStateSpace->searchgoalstate = NULL; 01090 //pSearchStateSpace->searchstartstate = GetState(SearchStartStateID); 01091 pSearchStateSpace->searchstartstate = NULL; 01092 01093 01094 pSearchStateSpace->bReinitializeSearchStateSpace = true; 01095 01096 return 1; 01097 01098 } 01099 01100 01101 int RSTARPlanner::SetSearchGoalState(int SearchGoalStateID) 01102 { 01103 if(pSearchStateSpace->searchgoalstate == NULL || 01104 pSearchStateSpace->searchgoalstate->StateID != SearchGoalStateID) 01105 { 01106 pSearchStateSpace->searchgoalstate = GetState(SearchGoalStateID); 01107 01108 //should be new search iteration 01109 pSearchStateSpace->eps_satisfied = INFINITECOST; 01110 pSearchStateSpace->bNewSearchIteration = true; 01111 pSearchStateSpace->eps = this->finitial_eps; 01112 01113 //recompute heuristic for the heap if heuristics are used 01114 #if USE_HEUR 01115 for(int i = 0; i < (int)pSearchStateSpace->searchMDP.StateArray.size(); i++) 01116 { 01117 CMDPSTATE* MDPstate = pSearchStateSpace->searchMDP.StateArray[i]; 01118 RSTARState* state = (RSTARState*)MDPstate->PlannerSpecificData; 01119 state->h = ComputeHeuristic(MDPstate); 01120 } 01121 01122 pSearchStateSpace->bReevaluatefvals = true; 01123 #endif 01124 } 01125 01126 01127 return 1; 01128 01129 } 01130 01131 01132 int RSTARPlanner::SetSearchStartState(int SearchStartStateID) 01133 { 01134 01135 CMDPSTATE* MDPstate = GetState(SearchStartStateID); 01136 01137 if(MDPstate != pSearchStateSpace->searchstartstate) 01138 { 01139 pSearchStateSpace->searchstartstate = MDPstate; 01140 pSearchStateSpace->bReinitializeSearchStateSpace = true; 01141 pSearchStateSpace->eps_satisfied = INFINITECOST; 01142 } 01143 01144 return 1; 01145 01146 } 01147 01148 01149 01150 void RSTARPlanner::PrintSearchState(RSTARState* state, FILE* fOut) 01151 { 01152 SBPL_FPRINTF(fOut, "state %d: h=%d g=%u iterc=%d callnuma=%d heapind=%d \n", 01153 state->MDPstate->StateID, state->h, state->g, 01154 state->iterationclosed, state->callnumberaccessed, state->heapindex); 01155 environment_->PrintState(state->MDPstate->StateID, true, fOut); 01156 01157 } 01158 01159 01160 01161 int RSTARPlanner::getHeurValue(int StateID) 01162 { 01163 CMDPSTATE* MDPstate = GetState(StateID); 01164 RSTARState* searchstateinfo = (RSTARState*)MDPstate->PlannerSpecificData; 01165 return searchstateinfo->h; 01166 } 01167 01168 01169 vector<int> RSTARPlanner::GetSearchPath(int& solcost) 01170 { 01171 01172 vector<int> wholePathIds; 01173 RSTARState* rstargoalstate = (RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData; 01174 01175 //set the return path and other path related variables 01176 vector<CMDPACTION*> tempPathID; 01177 01178 //initially no path 01179 solcost = INFINITECOST; 01180 wholePathIds.clear(); 01181 01182 //special case when we are already at the goal 01183 if(rstargoalstate->MDPstate == pSearchStateSpace->searchstartstate) 01184 { 01185 solcost = 0; 01186 return wholePathIds; 01187 } 01188 01189 if(rstargoalstate->g >= INFINITECOST || rstargoalstate->bestpredaction == NULL || 01190 ((RSTARACTIONDATA*)rstargoalstate->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0) 01191 return wholePathIds; //no path to goal state was found 01192 01193 //path exists 01194 int pathcost = 0; 01195 RSTARState* rstarstate = rstargoalstate; 01196 while(rstarstate->bestpredaction != NULL && rstarstate->MDPstate != pSearchStateSpace->searchstartstate) 01197 { 01198 //get action data 01199 RSTARACTIONDATA* bestpredactiondata = (RSTARACTIONDATA*)rstarstate->bestpredaction->PlannerSpecificData; 01200 01201 //get predecessor in the search tree 01202 RSTARState* predstate = (RSTARState*)GetState(rstarstate->bestpredaction->SourceStateID)->PlannerSpecificData; 01203 01204 //check validity 01205 if(predstate->g + bestpredactiondata->clow != rstarstate->g) 01206 { 01207 SBPL_ERROR("ERROR: clow(=%d) + predstate.g(=%d) = %d != succstate.g = %d\n", 01208 bestpredactiondata->clow, predstate->g, bestpredactiondata->clow + predstate->g, rstarstate->g); 01209 SBPL_PRINTF("PredState: stateID=%d g=%d iterc=%d h=%d\n", predstate->MDPstate->StateID, predstate->g, predstate->iterationclosed, predstate->h); 01210 throw new SBPL_Exception(); 01211 } 01212 01213 //store the action and its cost 01214 tempPathID.push_back(rstarstate->bestpredaction); 01215 pathcost += rstarstate->bestpredaction->Costs[0]; 01216 01217 //go to the predecessor 01218 rstarstate = predstate; 01219 01220 //another check 01221 if(pathcost + rstarstate->g > rstargoalstate->g) 01222 { 01223 SBPL_ERROR("ERROR: pathcost+rstarstate.g = %d > goalstate.g = %d\n", pathcost + rstarstate->g, rstargoalstate->g); 01224 throw new SBPL_Exception(); 01225 } 01226 } 01227 01228 01229 //now recover the actual path 01230 RSTARACTIONDATA* actiondata; 01231 for(int aind = 0; aind < (int)tempPathID.size(); aind++) 01232 { 01233 if(bforwardsearch) 01234 actiondata = (RSTARACTIONDATA*)tempPathID.at(tempPathID.size() - aind - 1)->PlannerSpecificData; //getting path in reverse 01235 else 01236 actiondata = (RSTARACTIONDATA*)tempPathID.at(aind)->PlannerSpecificData; //getting path in reverse 01237 01238 //get the states that correspond to the high-level action 01239 for(int j = 0; j < (int)actiondata->pathIDs.size(); j++) 01240 { 01241 wholePathIds.push_back(actiondata->pathIDs.at(j)); //note: path corresponding to the action is already in right direction 01242 } 01243 } 01244 SBPL_FPRINTF(fDeb, "high-level pathcost=%d and high-level g(searchgoal)=%d\n", pathcost, rstargoalstate->g); 01245 01246 //get the solcost 01247 solcost = pathcost; 01248 return wholePathIds; 01249 } 01250 01251 void RSTARPlanner::PrintSearchPath(FILE* fOut) 01252 { 01253 vector<int> pathIds; 01254 int solcost; 01255 01256 pathIds = GetSearchPath(solcost); 01257 01258 SBPL_FPRINTF(fOut, "high-level solution cost = %d, solution length=%d\n", solcost, (unsigned int)pathIds.size()); 01259 for(int sind = 0; sind < (int)pathIds.size(); sind++) 01260 { 01261 environment_->PrintState(pathIds.at(sind), false, fOut); 01262 } 01263 01264 } 01265 01266 bool RSTARPlanner::Search(vector<int>& pathIds, int & PathCost, bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs) 01267 { 01268 CKey key; 01269 TimeStarted = clock(); 01270 highlevel_searchexpands = 0; 01271 lowlevel_searchexpands = 0; 01272 01273 01274 #if DEBUG 01275 SBPL_FPRINTF(fDeb, "new search call (call number=%d)\n", pSearchStateSpace->callnumber); 01276 #endif 01277 01278 if(pSearchStateSpace->bReinitializeSearchStateSpace == true){ 01279 //re-initialize state space 01280 ReInitializeSearchStateSpace(); 01281 } 01282 01283 01284 if(bOptimalSolution) 01285 { 01286 pSearchStateSpace->eps = 1; 01287 MaxNumofSecs = INFINITECOST; 01288 } 01289 else if(bFirstSolution) 01290 { 01291 MaxNumofSecs = INFINITECOST; 01292 } 01293 01294 //get the size of environment that is already allocated 01295 int oldenvsize = environment_->StateID2IndexMapping.size()*sizeof(int); 01296 01297 //the main loop of R* 01298 int prevexpands = 0; 01299 clock_t loop_time; 01300 //TODO - change FINAL_EPS and DECREASE_EPS onto a parameter 01301 while(pSearchStateSpace->eps_satisfied > RSTAR_FINAL_EPS && 01302 (clock()- TimeStarted) < MaxNumofSecs*(double)CLOCKS_PER_SEC) 01303 { 01304 loop_time = clock(); 01305 01306 //decrease eps for all subsequent iterations 01307 if(fabs(pSearchStateSpace->eps_satisfied - pSearchStateSpace->eps) < ERR_EPS && !bFirstSolution) 01308 { 01309 pSearchStateSpace->eps = pSearchStateSpace->eps - RSTAR_DECREASE_EPS; 01310 if(pSearchStateSpace->eps < RSTAR_FINAL_EPS) 01311 pSearchStateSpace->eps = RSTAR_FINAL_EPS; 01312 01313 //the priorities need to be updated 01314 pSearchStateSpace->bReevaluatefvals = true; 01315 01316 //it will be a new search. Since R* is non-incremental, it will have to be a new call 01317 pSearchStateSpace->bNewSearchIteration = true; 01318 pSearchStateSpace->bReinitializeSearchStateSpace = true; 01319 } 01320 01321 if(pSearchStateSpace->bReinitializeSearchStateSpace == true){ 01322 //re-initialize state space 01323 ReInitializeSearchStateSpace(); 01324 } 01325 01326 if(pSearchStateSpace->bNewSearchIteration) 01327 { 01328 pSearchStateSpace->searchiteration++; 01329 pSearchStateSpace->bNewSearchIteration = false; 01330 } 01331 01332 //re-compute f-values if necessary and reorder the heap 01333 if(pSearchStateSpace->bReevaluatefvals) 01334 Reevaluatefvals(); 01335 01336 //improve or compute path 01337 if(ImprovePath(MaxNumofSecs) == 1){ 01338 pSearchStateSpace->eps_satisfied = pSearchStateSpace->eps; //note: eps is satisfied probabilistically 01339 } 01340 01341 //print the solution cost and eps bound 01342 SBPL_PRINTF("eps=%f highlevel expands=%d g(searchgoal)=%d time=%.3f\n", pSearchStateSpace->eps_satisfied, highlevel_searchexpands - prevexpands, 01343 ((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g,double(clock()-loop_time)/CLOCKS_PER_SEC); 01344 01345 #if DEBUG 01346 SBPL_FPRINTF(fDeb, "eps=%f highlevel expands=%d g(searchgoal)=%d time=%.3f\n", pSearchStateSpace->eps_satisfied, highlevel_searchexpands - prevexpands, 01347 ((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g,double(clock()-loop_time)/CLOCKS_PER_SEC); 01348 PrintSearchState((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData, fDeb); 01349 #endif 01350 prevexpands = highlevel_searchexpands; 01351 01352 01353 //if just the first solution then we are done 01354 if(bFirstSolution) 01355 break; 01356 01357 //no solution exists 01358 if(((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g == INFINITECOST) 01359 break; 01360 01361 } 01362 01363 01364 #if DEBUG 01365 SBPL_FFLUSH(fDeb); 01366 #endif 01367 01368 PathCost = ((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; 01369 if(((RSTARACTIONDATA*)((RSTARState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->bestpredaction->PlannerSpecificData)->pathIDs.size() == 0) 01370 PathCost = INFINITECOST; //the path to the goal is not found, it is just goal has been generated but the last edge to it wasn't computed yet 01371 01372 MaxMemoryCounter += (oldenvsize - environment_->StateID2IndexMapping.size()*sizeof(int)); 01373 01374 SBPL_PRINTF("MaxMemoryCounter = %d\n", MaxMemoryCounter); 01375 01376 int solcost = INFINITECOST; 01377 bool ret = false; 01378 if(PathCost == INFINITECOST) 01379 { 01380 SBPL_PRINTF("could not find a solution\n"); 01381 ret = false; 01382 } 01383 else 01384 { 01385 SBPL_PRINTF("solution is found\n"); 01386 pathIds = GetSearchPath(solcost); 01387 ret = true; 01388 } 01389 01390 SBPL_PRINTF("total highlevel expands this call = %d, planning time = %.3f secs, solution cost=%d\n", 01391 highlevel_searchexpands, (clock()-TimeStarted)/((double)CLOCKS_PER_SEC), solcost); 01392 01393 01394 //SBPL_FPRINTF(fStat, "%d %d\n", highlevel_searchexpands, solcost); 01395 01396 return ret; 01397 01398 } 01399 01400 01401 //-----------------------------Interface function----------------------------------------------------- 01402 //returns 1 if found a solution, and 0 otherwise 01403 int RSTARPlanner::replan(double allocated_time_secs, vector<int>* solution_stateIDs_V) 01404 { 01405 int solcost; 01406 01407 return replan(allocated_time_secs, solution_stateIDs_V, &solcost); 01408 01409 } 01410 01411 //returns 1 if found a solution, and 0 otherwise 01412 int RSTARPlanner::replan(double allocated_time_secs, vector<int>* solution_stateIDs_V, int* psolcost) 01413 { 01414 vector<int> pathIds; 01415 bool bFound = false; 01416 int PathCost; 01417 bool bFirstSolution = this->bsearchuntilfirstsolution; 01418 bool bOptimalSolution = false; 01419 *psolcost = 0; 01420 01421 SBPL_PRINTF("planner: replan called (bFirstSol=%d, bOptSol=%d)\n", bFirstSolution, bOptimalSolution); 01422 01423 //plan 01424 if((bFound = Search(pathIds, PathCost, bFirstSolution, bOptimalSolution, allocated_time_secs)) == false) 01425 { 01426 SBPL_PRINTF("failed to find a solution\n"); 01427 } 01428 01429 //copy the solution 01430 *solution_stateIDs_V = pathIds; 01431 *psolcost = PathCost; 01432 01433 return (int)bFound; 01434 01435 } 01436 01437 01438 int RSTARPlanner::set_goal(int goal_stateID) 01439 { 01440 01441 SBPL_PRINTF("planner: setting goal to %d\n", goal_stateID); 01442 environment_->PrintState(goal_stateID, true, stdout); 01443 01444 if(bforwardsearch) 01445 { 01446 if(SetSearchGoalState(goal_stateID) != 1) 01447 { 01448 SBPL_ERROR("ERROR: failed to set search goal state\n"); 01449 return 0; 01450 } 01451 } 01452 else 01453 { 01454 if(SetSearchStartState(goal_stateID) != 1) 01455 { 01456 SBPL_ERROR("ERROR: failed to set search start state\n"); 01457 return 0; 01458 } 01459 } 01460 01461 return 1; 01462 } 01463 01464 01465 int RSTARPlanner::set_start(int start_stateID) 01466 { 01467 01468 SBPL_PRINTF("planner: setting start to %d\n", start_stateID); 01469 environment_->PrintState(start_stateID, true, stdout); 01470 01471 if(bforwardsearch) 01472 { 01473 01474 if(SetSearchStartState(start_stateID) != 1) 01475 { 01476 SBPL_ERROR("ERROR: failed to set search start state\n"); 01477 return 0; 01478 } 01479 } 01480 else 01481 { 01482 if(SetSearchGoalState(start_stateID) != 1) 01483 { 01484 SBPL_ERROR("ERROR: failed to set search goal state\n"); 01485 return 0; 01486 } 01487 } 01488 01489 return 1; 01490 01491 } 01492 01493 01494 01495 void RSTARPlanner::costs_changed(StateChangeQuery const & stateChange) 01496 { 01497 //since R* is non-incremental 01498 pSearchStateSpace->bReinitializeSearchStateSpace = true; 01499 01500 } 01501 01502 void RSTARPlanner::costs_changed() 01503 { 01504 //since R* is non-incremental 01505 pSearchStateSpace->bReinitializeSearchStateSpace = true; 01506 01507 } 01508 01509 01510 01511 int RSTARPlanner::force_planning_from_scratch() 01512 { 01513 SBPL_PRINTF("planner: forceplanfromscratch set\n"); 01514 01515 pSearchStateSpace->bReinitializeSearchStateSpace = true; 01516 01517 return 1; 01518 } 01519 01520 01521 int RSTARPlanner::set_search_mode(bool bSearchUntilFirstSolution) 01522 { 01523 01524 SBPL_PRINTF("planner: search mode set to %d\n", bSearchUntilFirstSolution); 01525 01526 bsearchuntilfirstsolution = bSearchUntilFirstSolution; 01527 01528 return 1; 01529 } 01530 01531 01532 void RSTARPlanner::print_searchpath(FILE* fOut) 01533 { 01534 PrintSearchPath(fOut); 01535 } 01536 01537 01538 //--------------------------------------------------------------------------------------------------------- 01539