ANAplanner.h
Go to the documentation of this file.
00001 /*
00002  * This code was used for generating experimental data for the purpose of understanding the performance of
00003  * the Anytime Nonparametric A* (ANA*) algorithm.  
00004  * The authors of this algorithm are Jur van den Berg, Rajat Shah, Arthur Huang and Ken Goldberg.
00005  * The code is available at http://goldberg.berkeley.edu/ana/
00006  * 
00007  */
00008 
00009 
00010 
00011 #ifndef __anaPLANNER_H_
00012 #define __anaPLANNER_H_
00013 
00014 
00015 //---configuration----
00016 
00017 //control of EPS
00018 //initial suboptimality bound (cost solution <= cost(eps*cost optimal solution)
00019 #define ana_DEFAULT_INITIAL_EPS     100000.0
00020 //as planning time exist, ana* decreases epsilon bound
00021 #define ana_DECREASE_EPS    0.2
00022 //final epsilon bound
00023 #define ana_FINAL_EPS       1.0
00024 
00025 
00026 //---------------------
00027 
00028 #define ana_INCONS_LIST_ID 0
00029 
00030 class CMDP;
00031 class CMDPSTATE;
00032 class CMDPACTION;
00033 class CHeap;
00034 
00035 
00036 //-------------------------------------------------------------
00037 
00038 
00041 typedef class anaSEARCHSTATEDATA : public AbstractSearchState
00042 {
00043 public:
00046         CMDPSTATE* MDPstate; 
00049         unsigned int v;
00052         unsigned int g;
00055         short unsigned int iterationclosed;
00058         short unsigned int callnumberaccessed;
00061         short unsigned int numofexpands;
00064         CMDPSTATE *bestpredstate;
00067         CMDPSTATE  *bestnextstate;
00068         unsigned int costtobestnextstate;
00069         int h;
00070 
00071         
00072 public:
00073         anaSEARCHSTATEDATA() {};        
00074         ~anaSEARCHSTATEDATA() {};
00075 } anaState;
00076 
00077 
00078 
00081 typedef struct anaSEARCHSTATESPACE
00082 {
00083         unsigned int G; 
00084 
00085         double eps;
00086   double eps_satisfied;
00087         CHeap* heap;
00088         
00089         short unsigned int searchiteration;
00090         short unsigned int callnumber;
00091         CMDPSTATE* searchgoalstate;
00092         CMDPSTATE* searchstartstate;
00093         
00094         CMDP searchMDP;
00095 
00096         bool bReevaluatefvals;
00097   bool bReinitializeSearchStateSpace;
00098         bool bNewSearchIteration;
00099 
00100 } anaSearchStateSpace_t;
00101 
00102 
00103 
00106 class anaPlanner : public SBPLPlanner
00107 {
00108 
00109 public:
00110 
00113         int replan(double allocated_time_secs, vector<int>* solution_stateIDs_V);
00116         int replan(double allocated_time_sec, vector<int>* solution_stateIDs_V, int* solcost);
00117 
00120     int set_goal(int goal_stateID);
00123     int set_start(int start_stateID);
00124 
00127     void costs_changed(StateChangeQuery const & stateChange);
00128 
00132     void costs_changed();
00133 
00134 
00137          int force_planning_from_scratch(); 
00138 
00141         int set_search_mode(bool bSearchUntilFirstSolution);
00142 
00145         virtual double get_solution_eps() const {return pSearchStateSpace_->eps_satisfied;};
00146 
00149     virtual int get_n_expands() const { return searchexpands; }
00150 
00153         virtual void set_initialsolution_eps(double initialsolution_eps) {finitial_eps = initialsolution_eps;};
00154 
00157         void print_searchpath(FILE* fOut);
00158 
00159 
00162     anaPlanner(DiscreteSpaceInformation* environment, bool bforwardsearch);
00165     ~anaPlanner();
00166 
00167         
00168 
00169 private:
00170 
00171         //member variables
00172         double finitial_eps;
00173         MDPConfig* MDPCfg_;
00174 
00175         bool bforwardsearch; //if true, then search proceeds forward, otherwise backward
00176 
00177         bool bsearchuntilfirstsolution; //if true, then search until first solution only (see planner.h for search modes)
00178 
00179     anaSearchStateSpace_t* pSearchStateSpace_;
00180 
00181         unsigned int searchexpands;
00182         int MaxMemoryCounter;
00183         clock_t TimeStarted;
00184         FILE *fDeb;
00185 
00186 
00187 
00188         
00189 
00190 
00191         void Initialize_searchinfo(CMDPSTATE* state, anaSearchStateSpace_t* pSearchStateSpace);
00192 
00193         CMDPSTATE* CreateState(int stateID, anaSearchStateSpace_t* pSearchStateSpace);
00194 
00195         CMDPSTATE* GetState(int stateID, anaSearchStateSpace_t* pSearchStateSpace);
00196 
00197         int ComputeHeuristic(CMDPSTATE* MDPstate, anaSearchStateSpace_t* pSearchStateSpace);
00198 
00199         //initialization of a state
00200         void InitializeSearchStateInfo(anaState* state, anaSearchStateSpace_t* pSearchStateSpace);
00201 
00202         //re-initialization of a state
00203         void ReInitializeSearchStateInfo(anaState* state, anaSearchStateSpace_t* pSearchStateSpace);
00204 
00205         void DeleteSearchStateData(anaState* state);
00206 
00207 // NEW FUNCTION
00208         double get_e_value(anaSearchStateSpace_t* pSearchStateSpace, int stateID);
00209 
00210         
00211         //used for backward search
00212         void UpdatePreds(anaState* state, anaSearchStateSpace_t* pSearchStateSpace);
00213 
00214 
00215         //used for forward search
00216         void UpdateSuccs(anaState* state, anaSearchStateSpace_t* pSearchStateSpace);
00217 
00218         int GetGVal(int StateID, anaSearchStateSpace_t* pSearchStateSpace);
00219 
00220         //returns 1 if the solution is found, 0 if the solution does not exist and 2 if it ran out of time
00221         int ImprovePath(anaSearchStateSpace_t* pSearchStateSpace, double MaxNumofSecs);
00222 
00223         void BuildNewOPENList(anaSearchStateSpace_t* pSearchStateSpace);
00224 
00225         void Reevaluatefvals(anaSearchStateSpace_t* pSearchStateSpace);
00226 
00227         //creates (allocates memory) search state space
00228         //does not initialize search statespace
00229         int CreateSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace);
00230 
00231         //deallocates memory used by SearchStateSpace
00232         void DeleteSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace);
00233 
00234         //debugging 
00235         void PrintSearchState(anaState* state, FILE* fOut);
00236 
00237 
00238         //reset properly search state space
00239         //needs to be done before deleting states
00240         int ResetSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace);
00241 
00242         //initialization before each search
00243         void ReInitializeSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace);
00244 
00245         //very first initialization
00246         int InitializeSearchStateSpace(anaSearchStateSpace_t* pSearchStateSpace);
00247 
00248         int SetSearchGoalState(int SearchGoalStateID, anaSearchStateSpace_t* pSearchStateSpace);
00249 
00250 
00251         int SetSearchStartState(int SearchStartStateID, anaSearchStateSpace_t* pSearchStateSpace);
00252 
00253         //reconstruct path functions are only relevant for forward search
00254         int ReconstructPath(anaSearchStateSpace_t* pSearchStateSpace);
00255 
00256 
00257         void PrintSearchPath(anaSearchStateSpace_t* pSearchStateSpace, FILE* fOut);
00258 
00259         int getHeurValue(anaSearchStateSpace_t* pSearchStateSpace, int StateID);
00260 
00261         //get path 
00262         vector<int> GetSearchPath(anaSearchStateSpace_t* pSearchStateSpace, int& solcost);
00263 
00264 
00265         bool Search(anaSearchStateSpace_t* pSearchStateSpace, vector<int>& pathIds, int & PathCost, bool bFirstSolution, bool bOptimalSolution, double MaxNumofSecs);
00266 
00267 
00268 };
00269 
00270 
00271 #endif
00272 
00273 
00274 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


sbpl
Author(s): Maxim Likhachev/maximl@seas.upenn.edu
autogenerated on Fri Jan 18 2013 13:41:52