$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 00036 00037 //----------------------------------------------------------------------------------------------------- 00038 00039 ARAPlanner::ARAPlanner(DiscreteSpaceInformation* environment, bool bSearchForward) 00040 { 00041 bforwardsearch = bSearchForward; 00042 00043 environment_ = environment; 00044 00045 bsearchuntilfirstsolution = false; 00046 finitial_eps = ARA_DEFAULT_INITIAL_EPS; 00047 searchexpands = 0; 00048 MaxMemoryCounter = 0; 00049 00050 #ifndef ROS 00051 const char* debug = "debug.txt"; 00052 #endif 00053 fDeb = SBPL_FOPEN(debug, "w"); 00054 if(fDeb == NULL){ 00055 SBPL_ERROR("ERROR: could not open planner debug file\n"); 00056 throw new SBPL_Exception(); 00057 } 00058 00059 pSearchStateSpace_ = new ARASearchStateSpace_t; 00060 00061 00062 //create the ARA planner 00063 if(CreateSearchStateSpace(pSearchStateSpace_) != 1) 00064 { 00065 SBPL_ERROR("ERROR: failed to create statespace\n"); 00066 return; 00067 } 00068 00069 //set the start and goal states 00070 if(InitializeSearchStateSpace(pSearchStateSpace_) != 1) 00071 { 00072 SBPL_ERROR("ERROR: failed to create statespace\n"); 00073 return; 00074 } 00075 finitial_eps_planning_time = -1.0; 00076 final_eps_planning_time = -1.0; 00077 num_of_expands_initial_solution = 0; 00078 final_eps = -1.0; 00079 } 00080 00081 ARAPlanner::~ARAPlanner() 00082 { 00083 if(pSearchStateSpace_ != NULL){ 00084 //delete the statespace 00085 DeleteSearchStateSpace(pSearchStateSpace_); 00086 delete pSearchStateSpace_; 00087 } 00088 SBPL_FCLOSE(fDeb); 00089 } 00090 00091 00092 void ARAPlanner::Initialize_searchinfo(CMDPSTATE* state, ARASearchStateSpace_t* pSearchStateSpace) 00093 { 00094 00095 ARAState* searchstateinfo = (ARAState*)state->PlannerSpecificData; 00096 00097 searchstateinfo->MDPstate = state; 00098 InitializeSearchStateInfo(searchstateinfo, pSearchStateSpace); 00099 } 00100 00101 00102 CMDPSTATE* ARAPlanner::CreateState(int stateID, ARASearchStateSpace_t* pSearchStateSpace) 00103 { 00104 CMDPSTATE* state = NULL; 00105 00106 #if DEBUG 00107 if(environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND] != -1) 00108 { 00109 SBPL_ERROR("ERROR in CreateState: state already created\n"); 00110 throw new SBPL_Exception(); 00111 } 00112 #endif 00113 00114 //adds to the tail a state 00115 state = pSearchStateSpace->searchMDP.AddState(stateID); 00116 00117 //remember the index of the state 00118 environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND] = pSearchStateSpace->searchMDP.StateArray.size()-1; 00119 00120 #if DEBUG 00121 if(state != pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND]]) 00122 { 00123 SBPL_ERROR("ERROR in CreateState: invalid state index\n"); 00124 throw new SBPL_Exception(); 00125 } 00126 #endif 00127 00128 00129 //create search specific info 00130 state->PlannerSpecificData = (ARAState*)malloc(sizeof(ARAState)); 00131 Initialize_searchinfo(state, pSearchStateSpace); 00132 MaxMemoryCounter += sizeof(ARAState); 00133 00134 return state; 00135 00136 } 00137 00138 CMDPSTATE* ARAPlanner::GetState(int stateID, ARASearchStateSpace_t* pSearchStateSpace) 00139 { 00140 00141 if(stateID >= (int)environment_->StateID2IndexMapping.size()) 00142 { 00143 SBPL_ERROR("ERROR int GetState: stateID %d is invalid\n", stateID); 00144 throw new SBPL_Exception(); 00145 } 00146 00147 if(environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND] == -1) 00148 return CreateState(stateID, pSearchStateSpace); 00149 else 00150 return pSearchStateSpace->searchMDP.StateArray[environment_->StateID2IndexMapping[stateID][ARAMDP_STATEID2IND]]; 00151 00152 } 00153 00154 00155 00156 //----------------------------------------------------------------------------------------------------- 00157 00158 00159 00160 00161 int ARAPlanner::ComputeHeuristic(CMDPSTATE* MDPstate, ARASearchStateSpace_t* pSearchStateSpace) 00162 { 00163 //compute heuristic for search 00164 00165 if(bforwardsearch) 00166 { 00167 00168 #if MEM_CHECK == 1 00169 //int WasEn = DisableMemCheck(); 00170 #endif 00171 00172 //forward search: heur = distance from state to searchgoal which is Goal ARAState 00173 int retv = environment_->GetGoalHeuristic(MDPstate->StateID); 00174 00175 #if MEM_CHECK == 1 00176 //if (WasEn) 00177 // EnableMemCheck(); 00178 #endif 00179 00180 return retv; 00181 00182 } 00183 else 00184 { 00185 //backward search: heur = distance from searchgoal to state 00186 return environment_->GetStartHeuristic(MDPstate->StateID); 00187 } 00188 } 00189 00190 00191 //initialization of a state 00192 void ARAPlanner::InitializeSearchStateInfo(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace) 00193 { 00194 state->g = INFINITECOST; 00195 state->v = INFINITECOST; 00196 state->iterationclosed = 0; 00197 state->callnumberaccessed = pSearchStateSpace->callnumber; 00198 state->bestnextstate = NULL; 00199 state->costtobestnextstate = INFINITECOST; 00200 state->heapindex = 0; 00201 state->listelem[ARA_INCONS_LIST_ID] = 0; 00202 state->numofexpands = 0; 00203 00204 state->bestpredstate = NULL; 00205 00206 //compute heuristics 00207 #if USE_HEUR 00208 if(pSearchStateSpace->searchgoalstate != NULL) 00209 state->h = ComputeHeuristic(state->MDPstate, pSearchStateSpace); 00210 else 00211 state->h = 0; 00212 #else 00213 state->h = 0; 00214 #endif 00215 00216 00217 } 00218 00219 00220 00221 //re-initialization of a state 00222 void ARAPlanner::ReInitializeSearchStateInfo(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace) 00223 { 00224 state->g = INFINITECOST; 00225 state->v = INFINITECOST; 00226 state->iterationclosed = 0; 00227 state->callnumberaccessed = pSearchStateSpace->callnumber; 00228 state->bestnextstate = NULL; 00229 state->costtobestnextstate = INFINITECOST; 00230 state->heapindex = 0; 00231 state->listelem[ARA_INCONS_LIST_ID] = 0; 00232 state->numofexpands = 0; 00233 00234 state->bestpredstate = NULL; 00235 00236 //compute heuristics 00237 #if USE_HEUR 00238 00239 if(pSearchStateSpace->searchgoalstate != NULL) 00240 { 00241 state->h = ComputeHeuristic(state->MDPstate, pSearchStateSpace); 00242 } 00243 else 00244 state->h = 0; 00245 00246 #else 00247 00248 state->h = 0; 00249 00250 #endif 00251 00252 00253 } 00254 00255 00256 00257 void ARAPlanner::DeleteSearchStateData(ARAState* state) 00258 { 00259 //no memory was allocated 00260 MaxMemoryCounter = 0; 00261 return; 00262 } 00263 00264 00265 00266 //used for backward search 00267 void ARAPlanner::UpdatePreds(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace) 00268 { 00269 vector<int> PredIDV; 00270 vector<int> CostV; 00271 CKey key; 00272 ARAState *predstate; 00273 00274 environment_->GetPreds(state->MDPstate->StateID, &PredIDV, &CostV); 00275 00276 //iterate through predecessors of s 00277 for(int pind = 0; pind < (int)PredIDV.size(); pind++) 00278 { 00279 CMDPSTATE* PredMDPState = GetState(PredIDV[pind], pSearchStateSpace); 00280 predstate = (ARAState*)(PredMDPState->PlannerSpecificData); 00281 if(predstate->callnumberaccessed != pSearchStateSpace->callnumber) 00282 ReInitializeSearchStateInfo(predstate, pSearchStateSpace); 00283 00284 //see if we can improve the value of predstate 00285 if(predstate->g > state->v + CostV[pind]) 00286 { 00287 predstate->g = state->v + CostV[pind]; 00288 predstate->bestnextstate = state->MDPstate; 00289 predstate->costtobestnextstate = CostV[pind]; 00290 00291 //re-insert into heap if not closed yet 00292 if(predstate->iterationclosed != pSearchStateSpace->searchiteration) 00293 { 00294 key.key[0] = predstate->g + (int)(pSearchStateSpace->eps*predstate->h); 00295 //key.key[1] = predstate->h; 00296 if(predstate->heapindex != 0) 00297 pSearchStateSpace->heap->updateheap(predstate,key); 00298 else 00299 pSearchStateSpace->heap->insertheap(predstate,key); 00300 } 00301 //take care of incons list 00302 else if(predstate->listelem[ARA_INCONS_LIST_ID] == NULL) 00303 { 00304 pSearchStateSpace->inconslist->insert(predstate, ARA_INCONS_LIST_ID); 00305 } 00306 } 00307 } //for predecessors 00308 00309 } 00310 00311 //used for forward search 00312 void ARAPlanner::UpdateSuccs(ARAState* state, ARASearchStateSpace_t* pSearchStateSpace) 00313 { 00314 vector<int> SuccIDV; 00315 vector<int> CostV; 00316 CKey key; 00317 ARAState *succstate; 00318 00319 environment_->GetSuccs(state->MDPstate->StateID, &SuccIDV, &CostV); 00320 00321 //iterate through predecessors of s 00322 for(int sind = 0; sind < (int)SuccIDV.size(); sind++) 00323 { 00324 CMDPSTATE* SuccMDPState = GetState(SuccIDV[sind], pSearchStateSpace); 00325 int cost = CostV[sind]; 00326 00327 succstate = (ARAState*)(SuccMDPState->PlannerSpecificData); 00328 if(succstate->callnumberaccessed != pSearchStateSpace->callnumber) 00329 ReInitializeSearchStateInfo(succstate, pSearchStateSpace); 00330 00331 //see if we can improve the value of succstate 00332 //taking into account the cost of action 00333 if(succstate->g > state->v + cost) 00334 { 00335 succstate->g = state->v + cost; 00336 succstate->bestpredstate = state->MDPstate; 00337 00338 //re-insert into heap if not closed yet 00339 if(succstate->iterationclosed != pSearchStateSpace->searchiteration) 00340 { 00341 00342 key.key[0] = succstate->g + (int)(pSearchStateSpace->eps*succstate->h); 00343 00344 //key.key[1] = succstate->h; 00345 00346 if(succstate->heapindex != 0) 00347 pSearchStateSpace->heap->updateheap(succstate,key); 00348 else 00349 pSearchStateSpace->heap->insertheap(succstate,key); 00350 } 00351 //take care of incons list 00352 else if(succstate->listelem[ARA_INCONS_LIST_ID] == NULL) 00353 { 00354 pSearchStateSpace->inconslist->insert(succstate, ARA_INCONS_LIST_ID); 00355 } 00356 } //check for cost improvement 00357 00358 } //for actions 00359 } 00360 00361 //TODO-debugmax - add obsthresh and other thresholds to other environments in 3dkin 00362 int ARAPlanner::GetGVal(int StateID, ARASearchStateSpace_t* pSearchStateSpace) 00363 { 00364 CMDPSTATE* cmdp_state = GetState(StateID, pSearchStateSpace); 00365 ARAState* state = (ARAState*)cmdp_state->PlannerSpecificData; 00366 return state->g; 00367 } 00368 00369 //returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time 00370 int ARAPlanner::ImprovePath(ARASearchStateSpace_t* pSearchStateSpace, double MaxNumofSecs) 00371 { 00372 int expands; 00373 ARAState *state, *searchgoalstate; 00374 CKey key, minkey; 00375 CKey goalkey; 00376 00377 expands = 0; 00378 00379 00380 if(pSearchStateSpace->searchgoalstate == NULL) 00381 { 00382 SBPL_ERROR("ERROR searching: no goal state is set\n"); 00383 throw new SBPL_Exception(); 00384 } 00385 00386 //goal state 00387 searchgoalstate = (ARAState*)(pSearchStateSpace->searchgoalstate->PlannerSpecificData); 00388 if(searchgoalstate->callnumberaccessed != pSearchStateSpace->callnumber) 00389 ReInitializeSearchStateInfo(searchgoalstate, pSearchStateSpace); 00390 00391 //set goal key 00392 goalkey.key[0] = searchgoalstate->g; 00393 //goalkey.key[1] = searchgoalstate->h; 00394 00395 //expand states until done 00396 minkey = pSearchStateSpace->heap->getminkeyheap(); 00397 CKey oldkey = minkey; 00398 while(!pSearchStateSpace->heap->emptyheap() && minkey.key[0] < INFINITECOST && goalkey > minkey && 00399 (clock()-TimeStarted) < MaxNumofSecs*(double)CLOCKS_PER_SEC) 00400 { 00401 00402 //get the state 00403 state = (ARAState*)pSearchStateSpace->heap->deleteminheap(); 00404 00405 00406 #if DEBUG 00407 //SBPL_FPRINTF(fDeb, "expanding state(%d): h=%d g=%u key=%u v=%u iterc=%d callnuma=%d expands=%d (g(goal)=%u)\n", 00408 // state->MDPstate->StateID, state->h, state->g, state->g+(int)(pSearchStateSpace->eps*state->h), state->v, 00409 // state->iterationclosed, state->callnumberaccessed, state->numofexpands, searchgoalstate->g); 00410 //SBPL_FPRINTF(fDeb, "expanding: "); 00411 //PrintSearchState(state, fDeb); 00412 if(state->listelem[ARA_INCONS_LIST_ID] != NULL) 00413 { 00414 SBPL_FPRINTF(fDeb, "ERROR: expanding a state from inconslist\n"); 00415 SBPL_ERROR("ERROR: expanding a state from inconslist\n"); 00416 throw new SBPL_Exception(); 00417 } 00418 //SBPL_FFLUSH(fDeb); 00419 #endif 00420 00421 #if DEBUG 00422 if(minkey.key[0] < oldkey.key[0] && fabs(this->finitial_eps - 1.0) < ERR_EPS) 00423 { 00424 //SBPL_PRINTF("WARN in search: the sequence of keys decreases\n"); 00425 //throw new SBPL_Exception(); 00426 } 00427 oldkey = minkey; 00428 #endif 00429 00430 if(state->v == state->g) 00431 { 00432 SBPL_ERROR("ERROR: consistent state is being expanded\n"); 00433 #if DEBUG 00434 SBPL_FPRINTF(fDeb, "ERROR: consistent state is being expanded\n"); 00435 throw new SBPL_Exception(); 00436 #endif 00437 } 00438 00439 //recompute state value 00440 state->v = state->g; 00441 state->iterationclosed = pSearchStateSpace->searchiteration; 00442 00443 //new expand 00444 expands++; 00445 state->numofexpands++; 00446 00447 00448 if(bforwardsearch == false) 00449 UpdatePreds(state, pSearchStateSpace); 00450 else 00451 UpdateSuccs(state, pSearchStateSpace); 00452 00453 //recompute minkey 00454 minkey = pSearchStateSpace->heap->getminkeyheap(); 00455 00456 //recompute goalkey if necessary 00457 if(goalkey.key[0] != (int)searchgoalstate->g) 00458 { 00459 //SBPL_PRINTF("re-computing goal key\n"); 00460 //recompute the goal key (heuristics should be zero) 00461 goalkey.key[0] = searchgoalstate->g; 00462 //goalkey.key[1] = searchgoalstate->h; 00463 } 00464 00465 if(expands%100000 == 0 && expands > 0) 00466 { 00467 SBPL_PRINTF("expands so far=%u\n", expands); 00468 } 00469 00470 } 00471 00472 int retv = 1; 00473 if(searchgoalstate->g == INFINITECOST && pSearchStateSpace->heap->emptyheap()) 00474 { 00475 SBPL_PRINTF("solution does not exist: search exited because heap is empty\n"); 00476 retv = 0; 00477 } 00478 else if(!pSearchStateSpace->heap->emptyheap() && goalkey > minkey) 00479 { 00480 SBPL_PRINTF("search exited because it ran out of time\n"); 00481 retv = 2; 00482 } 00483 else if(searchgoalstate->g == INFINITECOST && !pSearchStateSpace->heap->emptyheap()) 00484 { 00485 SBPL_PRINTF("solution does not exist: search exited because all candidates for expansion have infinite heuristics\n"); 00486 retv = 0; 00487 } 00488 else 00489 { 00490 SBPL_PRINTF("search exited with a solution for eps=%.3f\n", pSearchStateSpace->eps); 00491 retv = 1; 00492 } 00493 00494 //SBPL_FPRINTF(fDeb, "expanded=%d\n", expands); 00495 00496 searchexpands += expands; 00497 00498 return retv; 00499 } 00500 00501 00502 void ARAPlanner::BuildNewOPENList(ARASearchStateSpace_t* pSearchStateSpace) 00503 { 00504 ARAState *state; 00505 CKey key; 00506 CHeap* pheap = pSearchStateSpace->heap; 00507 CList* pinconslist = pSearchStateSpace->inconslist; 00508 00509 //move incons into open 00510 while(pinconslist->firstelement != NULL) 00511 { 00512 state = (ARAState*)pinconslist->firstelement->liststate; 00513 00514 //compute f-value 00515 key.key[0] = state->g + (int)(pSearchStateSpace->eps*state->h); 00516 //key.key[1] = state->h; 00517 00518 //insert into OPEN 00519 pheap->insertheap(state, key); 00520 //remove from INCONS 00521 pinconslist->remove(state, ARA_INCONS_LIST_ID); 00522 } 00523 } 00524 00525 00526 void ARAPlanner::Reevaluatefvals(ARASearchStateSpace_t* pSearchStateSpace) 00527 { 00528 CKey key; 00529 int i; 00530 CHeap* pheap = pSearchStateSpace->heap; 00531 00532 //recompute priorities for states in OPEN and reorder it 00533 for (i = 1; i <= pheap->currentsize; ++i) 00534 { 00535 ARAState* state = (ARAState*)pheap->heap[i].heapstate; 00536 pheap->heap[i].key.key[0] = state->g + 00537 (int)(pSearchStateSpace->eps*state->h); 00538 //pheap->heap[i].key.key[1] = state->h; 00539 } 00540 pheap->makeheap(); 00541 00542 pSearchStateSpace->bReevaluatefvals = false; 00543 } 00544 00545 00546 00547 00548 //creates (allocates memory) search state space 00549 //does not initialize search statespace 00550 int ARAPlanner::CreateSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) 00551 { 00552 00553 //create a heap 00554 pSearchStateSpace->heap = new CHeap; 00555 pSearchStateSpace->inconslist = new CList; 00556 MaxMemoryCounter += sizeof(CHeap); 00557 MaxMemoryCounter += sizeof(CList); 00558 00559 pSearchStateSpace->searchgoalstate = NULL; 00560 pSearchStateSpace->searchstartstate = NULL; 00561 00562 searchexpands = 0; 00563 00564 00565 pSearchStateSpace->bReinitializeSearchStateSpace = false; 00566 00567 return 1; 00568 } 00569 00570 //deallocates memory used by SearchStateSpace 00571 void ARAPlanner::DeleteSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) 00572 { 00573 if(pSearchStateSpace->heap != NULL) 00574 { 00575 pSearchStateSpace->heap->makeemptyheap(); 00576 delete pSearchStateSpace->heap; 00577 pSearchStateSpace->heap = NULL; 00578 } 00579 00580 if(pSearchStateSpace->inconslist != NULL) 00581 { 00582 pSearchStateSpace->inconslist->makeemptylist(ARA_INCONS_LIST_ID); 00583 delete pSearchStateSpace->inconslist; 00584 pSearchStateSpace->inconslist = NULL; 00585 } 00586 00587 //delete the states themselves 00588 int iend = (int)pSearchStateSpace->searchMDP.StateArray.size(); 00589 for(int i=0; i < iend; i++) 00590 { 00591 CMDPSTATE* state = pSearchStateSpace->searchMDP.StateArray[i]; 00592 if(state != NULL && state->PlannerSpecificData != NULL){ 00593 DeleteSearchStateData((ARAState*)state->PlannerSpecificData); 00594 free((ARAState*)state->PlannerSpecificData); 00595 state->PlannerSpecificData = NULL; 00596 } 00597 } 00598 pSearchStateSpace->searchMDP.Delete(); 00599 } 00600 00601 00602 00603 //reset properly search state space 00604 //needs to be done before deleting states 00605 int ARAPlanner::ResetSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) 00606 { 00607 pSearchStateSpace->heap->makeemptyheap(); 00608 pSearchStateSpace->inconslist->makeemptylist(ARA_INCONS_LIST_ID); 00609 00610 return 1; 00611 } 00612 00613 //initialization before each search 00614 void ARAPlanner::ReInitializeSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) 00615 { 00616 CKey key; 00617 00618 //increase callnumber 00619 pSearchStateSpace->callnumber++; 00620 00621 //reset iteration 00622 pSearchStateSpace->searchiteration = 0; 00623 pSearchStateSpace->bNewSearchIteration = true; 00624 00625 #if DEBUG 00626 SBPL_FPRINTF(fDeb, "reinitializing search state-space (new call number=%d search iter=%d)\n", 00627 pSearchStateSpace->callnumber,pSearchStateSpace->searchiteration ); 00628 #endif 00629 00630 00631 00632 pSearchStateSpace->heap->makeemptyheap(); 00633 pSearchStateSpace->inconslist->makeemptylist(ARA_INCONS_LIST_ID); 00634 00635 //reset 00636 pSearchStateSpace->eps = this->finitial_eps; 00637 pSearchStateSpace->eps_satisfied = INFINITECOST; 00638 00639 //initialize start state 00640 ARAState* startstateinfo = (ARAState*)(pSearchStateSpace->searchstartstate->PlannerSpecificData); 00641 if(startstateinfo->callnumberaccessed != pSearchStateSpace->callnumber) 00642 ReInitializeSearchStateInfo(startstateinfo, pSearchStateSpace); 00643 00644 startstateinfo->g = 0; 00645 00646 //insert start state into the heap 00647 key.key[0] = (long int)(pSearchStateSpace->eps*startstateinfo->h); 00648 //key.key[1] = startstateinfo->h; 00649 pSearchStateSpace->heap->insertheap(startstateinfo, key); 00650 00651 pSearchStateSpace->bReinitializeSearchStateSpace = false; 00652 pSearchStateSpace->bReevaluatefvals = false; 00653 } 00654 00655 //very first initialization 00656 int ARAPlanner::InitializeSearchStateSpace(ARASearchStateSpace_t* pSearchStateSpace) 00657 { 00658 00659 if(pSearchStateSpace->heap->currentsize != 0 || 00660 pSearchStateSpace->inconslist->currentsize != 0) 00661 { 00662 SBPL_ERROR("ERROR in InitializeSearchStateSpace: heap or list is not empty\n"); 00663 throw new SBPL_Exception(); 00664 } 00665 00666 pSearchStateSpace->eps = this->finitial_eps; 00667 pSearchStateSpace->eps_satisfied = INFINITECOST; 00668 pSearchStateSpace->searchiteration = 0; 00669 pSearchStateSpace->bNewSearchIteration = true; 00670 pSearchStateSpace->callnumber = 0; 00671 pSearchStateSpace->bReevaluatefvals = false; 00672 00673 00674 //create and set the search start state 00675 pSearchStateSpace->searchgoalstate = NULL; 00676 //pSearchStateSpace->searchstartstate = GetState(SearchStartStateID, pSearchStateSpace); 00677 pSearchStateSpace->searchstartstate = NULL; 00678 00679 00680 pSearchStateSpace->bReinitializeSearchStateSpace = true; 00681 00682 return 1; 00683 00684 } 00685 00686 00687 int ARAPlanner::SetSearchGoalState(int SearchGoalStateID, ARASearchStateSpace_t* pSearchStateSpace) 00688 { 00689 if(pSearchStateSpace->searchgoalstate == NULL || 00690 pSearchStateSpace->searchgoalstate->StateID != SearchGoalStateID) 00691 { 00692 pSearchStateSpace->searchgoalstate = GetState(SearchGoalStateID, pSearchStateSpace); 00693 00694 //should be new search iteration 00695 pSearchStateSpace->eps_satisfied = INFINITECOST; 00696 pSearchStateSpace->bNewSearchIteration = true; 00697 pSearchStateSpace_->eps = this->finitial_eps; 00698 00699 00700 //recompute heuristic for the heap if heuristics is used 00701 #if USE_HEUR 00702 for(int i = 0; i < (int)pSearchStateSpace->searchMDP.StateArray.size(); i++) 00703 { 00704 CMDPSTATE* MDPstate = pSearchStateSpace->searchMDP.StateArray[i]; 00705 ARAState* state = (ARAState*)MDPstate->PlannerSpecificData; 00706 state->h = ComputeHeuristic(MDPstate, pSearchStateSpace); 00707 } 00708 00709 pSearchStateSpace->bReevaluatefvals = true; 00710 #endif 00711 } 00712 00713 00714 return 1; 00715 00716 } 00717 00718 00719 int ARAPlanner::SetSearchStartState(int SearchStartStateID, ARASearchStateSpace_t* pSearchStateSpace) 00720 { 00721 00722 CMDPSTATE* MDPstate = GetState(SearchStartStateID, pSearchStateSpace); 00723 00724 if(MDPstate != pSearchStateSpace->searchstartstate) 00725 { 00726 pSearchStateSpace->searchstartstate = MDPstate; 00727 pSearchStateSpace->bReinitializeSearchStateSpace = true; 00728 } 00729 00730 return 1; 00731 00732 } 00733 00734 00735 00736 int ARAPlanner::ReconstructPath(ARASearchStateSpace_t* pSearchStateSpace) 00737 { 00738 00739 00740 if(bforwardsearch) //nothing to do, if search is backward 00741 { 00742 CMDPSTATE* MDPstate = pSearchStateSpace->searchgoalstate; 00743 CMDPSTATE* PredMDPstate; 00744 ARAState *predstateinfo, *stateinfo; 00745 00746 00747 00748 #if DEBUG 00749 SBPL_FPRINTF(fDeb, "reconstructing a path:\n"); 00750 #endif 00751 00752 while(MDPstate != pSearchStateSpace->searchstartstate) 00753 { 00754 stateinfo = (ARAState*)MDPstate->PlannerSpecificData; 00755 00756 #if DEBUG 00757 PrintSearchState(stateinfo, fDeb); 00758 #endif 00759 if(stateinfo->g == INFINITECOST) 00760 { 00761 //SBPL_ERROR("ERROR in ReconstructPath: g of the state on the path is INFINITE\n"); 00762 //throw new SBPL_Exception(); 00763 return -1; 00764 } 00765 00766 if(stateinfo->bestpredstate == NULL) 00767 { 00768 SBPL_ERROR("ERROR in ReconstructPath: bestpred is NULL\n"); 00769 throw new SBPL_Exception(); 00770 } 00771 00772 //get the parent state 00773 PredMDPstate = stateinfo->bestpredstate; 00774 predstateinfo = (ARAState*)PredMDPstate->PlannerSpecificData; 00775 00776 //set its best next info 00777 predstateinfo->bestnextstate = MDPstate; 00778 00779 //check the decrease of g-values along the path 00780 if(predstateinfo->v >= stateinfo->g) 00781 { 00782 SBPL_ERROR("ERROR in ReconstructPath: g-values are non-decreasing\n"); 00783 PrintSearchState(predstateinfo, fDeb); 00784 throw new SBPL_Exception(); 00785 } 00786 00787 //transition back 00788 MDPstate = PredMDPstate; 00789 } 00790 } 00791 00792 return 1; 00793 } 00794 00795 00796 00797 void ARAPlanner::PrintSearchPath(ARASearchStateSpace_t* pSearchStateSpace, FILE* fOut) 00798 { 00799 ARAState* searchstateinfo; 00800 CMDPSTATE* state; 00801 int goalID; 00802 int PathCost; 00803 00804 if(bforwardsearch) 00805 { 00806 state = pSearchStateSpace->searchstartstate; 00807 goalID = pSearchStateSpace->searchgoalstate->StateID; 00808 } 00809 else 00810 { 00811 state = pSearchStateSpace->searchgoalstate; 00812 goalID = pSearchStateSpace->searchstartstate->StateID; 00813 } 00814 if(fOut == NULL) 00815 fOut = stdout; 00816 00817 PathCost = ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; 00818 00819 SBPL_FPRINTF(fOut, "Printing a path from state %d to the goal state %d\n", 00820 state->StateID, pSearchStateSpace->searchgoalstate->StateID); 00821 SBPL_FPRINTF(fOut, "Path cost = %d:\n", PathCost); 00822 00823 00824 environment_->PrintState(state->StateID, false, fOut); 00825 00826 int costFromStart = 0; 00827 while(state->StateID != goalID) 00828 { 00829 SBPL_FPRINTF(fOut, "state %d ", state->StateID); 00830 00831 if(state->PlannerSpecificData == NULL) 00832 { 00833 SBPL_FPRINTF(fOut, "path does not exist since search data does not exist\n"); 00834 break; 00835 } 00836 00837 searchstateinfo = (ARAState*)state->PlannerSpecificData; 00838 00839 if(searchstateinfo->bestnextstate == NULL) 00840 { 00841 SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); 00842 break; 00843 } 00844 if(searchstateinfo->g == INFINITECOST) 00845 { 00846 SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); 00847 break; 00848 } 00849 00850 int costToGoal = PathCost - costFromStart; 00851 int transcost = searchstateinfo->g - ((ARAState*)(searchstateinfo->bestnextstate->PlannerSpecificData))->v; 00852 if(bforwardsearch) 00853 transcost = -transcost; 00854 00855 costFromStart += transcost; 00856 00857 SBPL_FPRINTF(fOut, "g=%d-->state %d, h = %d ctg = %d ", searchstateinfo->g, 00858 searchstateinfo->bestnextstate->StateID, searchstateinfo->h, costToGoal); 00859 00860 state = searchstateinfo->bestnextstate; 00861 00862 environment_->PrintState(state->StateID, false, fOut); 00863 00864 00865 00866 } 00867 } 00868 00869 void ARAPlanner::PrintSearchState(ARAState* state, FILE* fOut) 00870 { 00871 SBPL_FPRINTF(fOut, "state %d: h=%d g=%u v=%u iterc=%d callnuma=%d expands=%d heapind=%d inconslist=%d\n", 00872 state->MDPstate->StateID, state->h, state->g, state->v, 00873 state->iterationclosed, state->callnumberaccessed, state->numofexpands, state->heapindex, state->listelem[ARA_INCONS_LIST_ID]?1:0); 00874 environment_->PrintState(state->MDPstate->StateID, true, fOut); 00875 00876 } 00877 00878 00879 00880 int ARAPlanner::getHeurValue(ARASearchStateSpace_t* pSearchStateSpace, int StateID) 00881 { 00882 CMDPSTATE* MDPstate = GetState(StateID, pSearchStateSpace); 00883 ARAState* searchstateinfo = (ARAState*)MDPstate->PlannerSpecificData; 00884 return searchstateinfo->h; 00885 } 00886 00887 00888 vector<int> ARAPlanner::GetSearchPath(ARASearchStateSpace_t* pSearchStateSpace, int& solcost) 00889 { 00890 vector<int> SuccIDV; 00891 vector<int> CostV; 00892 vector<int> wholePathIds; 00893 ARAState* searchstateinfo; 00894 CMDPSTATE* state = NULL; 00895 CMDPSTATE* goalstate = NULL; 00896 CMDPSTATE* startstate=NULL; 00897 00898 if(bforwardsearch) 00899 { 00900 startstate = pSearchStateSpace->searchstartstate; 00901 goalstate = pSearchStateSpace->searchgoalstate; 00902 00903 //reconstruct the path by setting bestnextstate pointers appropriately 00904 ReconstructPath(pSearchStateSpace); 00905 } 00906 else 00907 { 00908 startstate = pSearchStateSpace->searchgoalstate; 00909 goalstate = pSearchStateSpace->searchstartstate; 00910 } 00911 00912 00913 state = startstate; 00914 00915 wholePathIds.push_back(state->StateID); 00916 solcost = 0; 00917 00918 FILE* fOut = stdout; 00919 if(fOut == NULL){ 00920 SBPL_ERROR("ERROR: could not open file\n"); 00921 throw new SBPL_Exception(); 00922 } 00923 while(state->StateID != goalstate->StateID) 00924 { 00925 if(state->PlannerSpecificData == NULL) 00926 { 00927 SBPL_FPRINTF(fOut, "path does not exist since search data does not exist\n"); 00928 break; 00929 } 00930 00931 searchstateinfo = (ARAState*)state->PlannerSpecificData; 00932 00933 if(searchstateinfo->bestnextstate == NULL) 00934 { 00935 SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); 00936 break; 00937 } 00938 if(searchstateinfo->g == INFINITECOST) 00939 { 00940 SBPL_FPRINTF(fOut, "path does not exist since bestnextstate == NULL\n"); 00941 break; 00942 } 00943 00944 environment_->GetSuccs(state->StateID, &SuccIDV, &CostV); 00945 int actioncost = INFINITECOST; 00946 for(int i = 0; i < (int)SuccIDV.size(); i++) 00947 { 00948 00949 if(SuccIDV.at(i) == searchstateinfo->bestnextstate->StateID && CostV.at(i)<actioncost) 00950 actioncost = CostV.at(i); 00951 00952 } 00953 if(actioncost == INFINITECOST) 00954 SBPL_PRINTF("WARNING: actioncost = %d\n", actioncost); 00955 00956 solcost += actioncost; 00957 00958 //SBPL_FPRINTF(fDeb, "actioncost=%d between states %d and %d\n", 00959 // actioncost, state->StateID, searchstateinfo->bestnextstate->StateID); 00960 //environment_->PrintState(state->StateID, false, fDeb); 00961 //environment_->PrintState(searchstateinfo->bestnextstate->StateID, false, fDeb); 00962 00963 00964 #if DEBUG 00965 ARAState* nextstateinfo = (ARAState*)(searchstateinfo->bestnextstate->PlannerSpecificData); 00966 if(actioncost != abs((int)(searchstateinfo->g - nextstateinfo->g)) && pSearchStateSpace->eps_satisfied <= 1.001) 00967 { 00968 SBPL_FPRINTF(fDeb, "ERROR: actioncost=%d is not matching the difference in g-values of %d\n", 00969 actioncost, abs((int)(searchstateinfo->g - nextstateinfo->g))); 00970 SBPL_ERROR("ERROR: actioncost=%d is not matching the difference in g-values of %d\n", 00971 actioncost,abs((int)(searchstateinfo->g - nextstateinfo->g))); 00972 PrintSearchState(searchstateinfo, fDeb); 00973 PrintSearchState(nextstateinfo, fDeb); 00974 } 00975 #endif 00976 00977 00978 state = searchstateinfo->bestnextstate; 00979 00980 wholePathIds.push_back(state->StateID); 00981 } 00982 00983 00984 return wholePathIds; 00985 } 00986 00987 00988 00989 bool ARAPlanner::Search(ARASearchStateSpace_t* pSearchStateSpace, vector<int>& pathIds, int & PathCost, bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs) 00990 { 00991 CKey key; 00992 TimeStarted = clock(); 00993 searchexpands = 0; 00994 00995 #if DEBUG 00996 SBPL_FPRINTF(fDeb, "new search call (call number=%d)\n", pSearchStateSpace->callnumber); 00997 #endif 00998 00999 if(pSearchStateSpace->bReinitializeSearchStateSpace == true){ 01000 //re-initialize state space 01001 ReInitializeSearchStateSpace(pSearchStateSpace); 01002 } 01003 01004 01005 if(bOptimalSolution) 01006 { 01007 pSearchStateSpace->eps = 1; 01008 MaxNumofSecs = INFINITECOST; 01009 } 01010 else if(bFirstSolution) 01011 { 01012 MaxNumofSecs = INFINITECOST; 01013 } 01014 01015 //ensure heuristics are up-to-date 01016 environment_->EnsureHeuristicsUpdated((bforwardsearch==true)); 01017 01018 //the main loop of ARA* 01019 int prevexpands = 0; 01020 clock_t loop_time; 01021 while(pSearchStateSpace->eps_satisfied > ARA_FINAL_EPS && 01022 (clock()- TimeStarted) < MaxNumofSecs*(double)CLOCKS_PER_SEC) 01023 { 01024 loop_time = clock(); 01025 //decrease eps for all subsequent iterations 01026 if(fabs(pSearchStateSpace->eps_satisfied - pSearchStateSpace->eps) < ERR_EPS && !bFirstSolution) 01027 { 01028 pSearchStateSpace->eps = pSearchStateSpace->eps - ARA_DECREASE_EPS; 01029 if(pSearchStateSpace->eps < ARA_FINAL_EPS) 01030 pSearchStateSpace->eps = ARA_FINAL_EPS; 01031 01032 //the priorities need to be updated 01033 pSearchStateSpace->bReevaluatefvals = true; 01034 01035 //it will be a new search 01036 pSearchStateSpace->bNewSearchIteration = true; 01037 01038 //build a new open list by merging it with incons one 01039 BuildNewOPENList(pSearchStateSpace); 01040 01041 } 01042 01043 if(pSearchStateSpace->bNewSearchIteration) 01044 { 01045 pSearchStateSpace->searchiteration++; 01046 pSearchStateSpace->bNewSearchIteration = false; 01047 } 01048 01049 //re-compute f-values if necessary and reorder the heap 01050 if(pSearchStateSpace->bReevaluatefvals) 01051 Reevaluatefvals(pSearchStateSpace); 01052 01053 //improve or compute path 01054 if(ImprovePath(pSearchStateSpace, MaxNumofSecs) == 1){ 01055 pSearchStateSpace->eps_satisfied = pSearchStateSpace->eps; 01056 } 01057 01058 //print the solution cost and eps bound 01059 SBPL_PRINTF("eps=%f expands=%d g(searchgoal)=%d time=%.3f\n", pSearchStateSpace->eps_satisfied, searchexpands - prevexpands, 01060 ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g,double(clock()-loop_time)/CLOCKS_PER_SEC); 01061 01062 if(pSearchStateSpace->eps_satisfied == finitial_eps && pSearchStateSpace->eps == finitial_eps) 01063 { 01064 finitial_eps_planning_time = double(clock()-loop_time)/CLOCKS_PER_SEC; 01065 num_of_expands_initial_solution = searchexpands - prevexpands; 01066 } 01067 01068 #if DEBUG 01069 SBPL_FPRINTF(fDeb, "eps=%f expands=%d g(searchgoal)=%d time=%.3f\n", pSearchStateSpace->eps_satisfied, searchexpands - prevexpands, 01070 ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g,double(clock()-loop_time)/CLOCKS_PER_SEC); 01071 PrintSearchState((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData, fDeb); 01072 #endif 01073 prevexpands = searchexpands; 01074 01075 01076 //if just the first solution then we are done 01077 if(bFirstSolution) 01078 break; 01079 01080 //no solution exists 01081 if(((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g == INFINITECOST) 01082 break; 01083 01084 } 01085 01086 01087 #if DEBUG 01088 SBPL_FFLUSH(fDeb); 01089 #endif 01090 01091 PathCost = ((ARAState*)pSearchStateSpace->searchgoalstate->PlannerSpecificData)->g; 01092 MaxMemoryCounter += environment_->StateID2IndexMapping.size()*sizeof(int); 01093 01094 SBPL_PRINTF("MaxMemoryCounter = %d\n", MaxMemoryCounter); 01095 01096 int solcost = INFINITECOST; 01097 bool ret = false; 01098 if(PathCost == INFINITECOST) 01099 { 01100 SBPL_PRINTF("could not find a solution\n"); 01101 ret = false; 01102 } 01103 else 01104 { 01105 SBPL_PRINTF("solution is found\n"); 01106 pathIds = GetSearchPath(pSearchStateSpace, solcost); 01107 ret = true; 01108 } 01109 01110 SBPL_PRINTF("total expands this call = %d, planning time = %.3f secs, solution cost=%d\n", 01111 searchexpands, (clock()-TimeStarted)/((double)CLOCKS_PER_SEC), solcost); 01112 final_eps_planning_time = (clock()-TimeStarted)/((double)CLOCKS_PER_SEC); 01113 final_eps = pSearchStateSpace->eps_satisfied; 01114 //SBPL_FPRINTF(fStat, "%d %d\n", searchexpands, solcost); 01115 01116 return ret; 01117 01118 } 01119 01120 01121 //-----------------------------Interface function----------------------------------------------------- 01122 //returns 1 if found a solution, and 0 otherwise 01123 int ARAPlanner::replan(double allocated_time_secs, vector<int>* solution_stateIDs_V) 01124 { 01125 int solcost; 01126 01127 return replan(allocated_time_secs, solution_stateIDs_V, &solcost); 01128 01129 } 01130 01131 //returns 1 if found a solution, and 0 otherwise 01132 int ARAPlanner::replan(double allocated_time_secs, vector<int>* solution_stateIDs_V, int* psolcost) 01133 { 01134 vector<int> pathIds; 01135 bool bFound = false; 01136 int PathCost; 01137 bool bFirstSolution = this->bsearchuntilfirstsolution; 01138 bool bOptimalSolution = false; 01139 *psolcost = 0; 01140 01141 SBPL_PRINTF("planner: replan called (bFirstSol=%d, bOptSol=%d)\n", bFirstSolution, bOptimalSolution); 01142 01143 //plan 01144 if((bFound = Search(pSearchStateSpace_, pathIds, PathCost, bFirstSolution, bOptimalSolution, allocated_time_secs)) == false) 01145 { 01146 SBPL_PRINTF("failed to find a solution\n"); 01147 } 01148 01149 //copy the solution 01150 *solution_stateIDs_V = pathIds; 01151 *psolcost = PathCost; 01152 01153 return (int)bFound; 01154 01155 } 01156 01157 01158 int ARAPlanner::set_goal(int goal_stateID) 01159 { 01160 01161 SBPL_PRINTF("planner: setting goal to %d\n", goal_stateID); 01162 environment_->PrintState(goal_stateID, true, stdout); 01163 01164 if(bforwardsearch) 01165 { 01166 if(SetSearchGoalState(goal_stateID, pSearchStateSpace_) != 1) 01167 { 01168 SBPL_ERROR("ERROR: failed to set search goal state\n"); 01169 return 0; 01170 } 01171 } 01172 else 01173 { 01174 if(SetSearchStartState(goal_stateID, pSearchStateSpace_) != 1) 01175 { 01176 SBPL_ERROR("ERROR: failed to set search start state\n"); 01177 return 0; 01178 } 01179 } 01180 01181 return 1; 01182 } 01183 01184 01185 int ARAPlanner::set_start(int start_stateID) 01186 { 01187 01188 SBPL_PRINTF("planner: setting start to %d\n", start_stateID); 01189 environment_->PrintState(start_stateID, true, stdout); 01190 01191 if(bforwardsearch) 01192 { 01193 01194 if(SetSearchStartState(start_stateID, pSearchStateSpace_) != 1) 01195 { 01196 SBPL_ERROR("ERROR: failed to set search start state\n"); 01197 return 0; 01198 } 01199 } 01200 else 01201 { 01202 if(SetSearchGoalState(start_stateID, pSearchStateSpace_) != 1) 01203 { 01204 SBPL_ERROR("ERROR: failed to set search goal state\n"); 01205 return 0; 01206 } 01207 } 01208 01209 return 1; 01210 01211 } 01212 01213 01214 01215 void ARAPlanner::costs_changed(StateChangeQuery const & stateChange) 01216 { 01217 01218 01219 pSearchStateSpace_->bReinitializeSearchStateSpace = true; 01220 01221 01222 } 01223 01224 void ARAPlanner::costs_changed() 01225 { 01226 01227 pSearchStateSpace_->bReinitializeSearchStateSpace = true; 01228 01229 } 01230 01231 01232 01233 int ARAPlanner::force_planning_from_scratch() 01234 { 01235 SBPL_PRINTF("planner: forceplanfromscratch set\n"); 01236 01237 pSearchStateSpace_->bReinitializeSearchStateSpace = true; 01238 01239 return 1; 01240 } 01241 01242 01243 int ARAPlanner::set_search_mode(bool bSearchUntilFirstSolution) 01244 { 01245 01246 SBPL_PRINTF("planner: search mode set to %d\n", bSearchUntilFirstSolution); 01247 01248 bsearchuntilfirstsolution = bSearchUntilFirstSolution; 01249 01250 return 1; 01251 } 01252 01253 01254 void ARAPlanner::print_searchpath(FILE* fOut) 01255 { 01256 PrintSearchPath(pSearchStateSpace_, fOut); 01257 } 01258 01259 01260 //--------------------------------------------------------------------------------------------------------- 01261