GlobalResource.h
Go to the documentation of this file.
00001 
00004 #ifndef GLOBALRESOURCE_H
00005 #define GLOBALRESOURCE_H
00006 
00007 #include <algorithm>
00008 #include <string>
00009 #include <iostream>
00010 #include <fstream>
00011 #include <sstream>
00012 
00013 #include "BeliefCache.h"
00014 #include "PointBasedAlgorithm.h"
00015 #include "CPTimer.h"
00016 #include "solverUtils.h"
00017 //#include "ActionSelector.h"
00018 //#include "BenchmarkEngine.h"
00019 
00020 #define MEMORY_USAGE_CHECK_INTERVAL 100
00021 
00022 using namespace std;
00023 
00024 namespace momdp
00025 {
00026         class GlobalResource
00027         {
00028         private:
00029                 int timeStamp;
00030                 //      CPTimer*        runtimeTimer;
00031 
00032                 GlobalResource();
00033                 int checkMemoryInterval;
00034 
00035 
00036         public:
00037                 SolverParams solverParams;
00038 
00039                 char* migsPathFile;
00040                 signed int migsPathFileNum;
00041                 bool migsUniformSamplingMileStone;
00042 
00043                 bool noPolicyOutput;
00044                 bool binaryPolicy;
00045                 int trialInterval;
00046                 int currTrial;
00047                 bool noSarsop;
00048 
00049                 SharedPointer<MOMDP> problem;
00050 
00051                 ~GlobalResource();
00052 
00053                 // Simulation, Evaluation Related 
00054                 bool simLookahead;
00055                 int simLen;
00056                 int simNum;
00057                 bool benchmarkMode;
00058                 int randSeed;
00059 
00060                 //ActionSelector* actS;
00061                 std::vector<double> expRewardRecord;
00062                 //GESTree *tree;
00063 
00064                 bool userTerminatedG; // the Ctrl+C flag set by the OfflineEngine.cc
00065 
00066                 bool solving;
00067                 bool mdpSolution;
00068 
00069 
00070                 int getTimeStamp();
00071                 void incTimeStamp(); // increment Time Stamp
00072                 void setTimeStamp(int newTimeStamp); //set Time Stamp
00073                 void init(); //dummy function,  run this once in the beginning of the program to ensure the object is created
00074                 double getRunTime(); // get the run time from the start, wall clock time
00075 
00076                 int hashCollision;
00077                 int hashRequest;
00078                 int hashSame;
00079 
00080                 int nInterStates;
00081                 int nSamples;
00082                 int nTimes;
00083 
00084                 double th;
00085                 double epi;
00086                 double stateGraphR;
00087                 int nInitMil;
00088 
00089                 unsigned long memoryUsage; // in bytes
00090 
00091                 //typedef int (*pbSolverHookType)(PointBasedAlgorithm *);
00092 
00093                 // vector<vector < pbSolverHookType> > pbSolverHooks;
00094                 CPTimer wallClockTotalTimer;
00095                 CPTimer solvingTimer;
00096                 CPTimer solvingOneTrialTimer;
00097 
00098 
00099                 //------------------------- stats variable
00100                 double pomdpLoadTime; // the time used to load POMDP spec files, < 0 means we are still loading it
00101                 double pomdpInitializationTime; // the time used to initialize, < 0 means we are still loading it
00102                 double gesGenStateMapTime;
00103                 double gesGenGuideMapTime;
00104                 double gesSampleTime;
00105                 double gesTrialTime;
00106                 double updGuideMapStartTime;
00107                 double totUpdGuideMapTime;
00108                 double limNotImproved;
00109 
00110                 // for dumping at interval
00111                 double lastIntervalSaveTime;
00112                 PointBasedAlgorithm* pbSolver;
00113                 int policyIndex;
00114                 void checkMemoryUsage();
00115 
00116                 // singleton pattern
00117 
00118                 static GlobalResource* singleInstance;
00119                 static GlobalResource* getInstance()
00120                 {
00121                         if( singleInstance == NULL)
00122                         {
00123                                 singleInstance = new GlobalResource();
00124                         }
00125                         return singleInstance;
00126                 }
00127 
00128 
00129                 // base name for current solution
00130                 string baseName;
00131 
00132                 static string parseBaseNameWithPath(string name);
00133                 static string parseBaseNameWithoutPath(string name);
00134 
00135                 void setBaseName(string basename)
00136                 {
00137                         baseName = basename;
00138                 }
00139                 string getBaseName()
00140                 {
00141                         return baseName;
00142                 }
00143 
00144                 // log files
00145 
00146                 int logLevel;
00147                 ofstream logFile;
00148                 void shutdown()
00149                 {
00150                         logFile.flush();
00151                         logFile.close();
00152                 }
00153 
00154                 void setLogLevel(int level)
00155                 {
00156                         logLevel = level;
00157                 }
00158 
00159                 // used to log some custom info 
00160                 void logEntry(string log)
00161                 {
00162                         if(!logFile.is_open())
00163                         {
00164                                 string logFileName = baseName+".log";
00165                                 logFile.open(logFileName.c_str());
00166                         }
00167                         logFile << log << endl;
00168                 }
00169 
00170                 void logInfo(string log)
00171                 {
00172                         if(logLevel > 2)
00173                         {
00174                                 logEntry(log);
00175                         }
00176                 }
00177 
00178                 void logWarn(string log)
00179                 {
00180                         if(logLevel > 1)
00181                         {
00182                                 logEntry(log);
00183                         }
00184                 }
00185 
00186                 void logError(string log)
00187                 {
00188                         if(logLevel > 0)
00189                         {
00190                                 logEntry(log);
00191                         }
00192                 }
00193 
00194                 void logCritical(string log)
00195                 {
00196                         logEntry(log);
00197                 }
00198 
00199                 void registerPBSolver(PointBasedAlgorithm* pSolver)
00200                 {
00201                         pbSolver = pSolver;
00202                 }
00203 
00204                 void PBSolverPrePOMDPLoad()
00205                 {
00206                         wallClockTotalTimer.start();
00207                 }
00208 
00209                 double PBSolverPostPOMDPLoad()
00210                 {
00211                         pomdpLoadTime = wallClockTotalTimer.elapsed();
00212                         return pomdpLoadTime;
00213                 }
00214 
00215                 void PBSolverPreInit()
00216                 {
00217                         solvingTimer.start();
00218                 }
00219                 void PBSolverPostInit();
00220 
00221                 void PBSolverPreGESSample()
00222                 {
00223                         gesSampleTime = solvingTimer.elapsed();
00224                 }
00225                 void PBSolverPostGESSample()
00226                 {
00227                         gesSampleTime = solvingTimer.elapsed() - gesSampleTime;
00228                         printf("time spent in GES Sample [%.2fs] \n", gesSampleTime);
00229                 }
00230 
00231                 void PBSolverPreGESGenStateMap()
00232                 {
00233                         gesGenStateMapTime = solvingTimer.elapsed();
00234                 }
00235                 void PBSolverPostGESGenStateMap()
00236                 {
00237                         gesGenStateMapTime = solvingTimer.elapsed() - gesGenStateMapTime;
00238                         printf("time spent in GES GenStateMap [%.2fs] \n", gesGenStateMapTime);
00239                 }
00240 
00241                 void PBSolverPreGESGenGuideMap()
00242                 {
00243                         gesGenGuideMapTime = solvingTimer.elapsed();
00244                 }
00245                 void PBSolverPostGESGenGuideMap()
00246                 {
00247                         gesGenGuideMapTime = solvingTimer.elapsed() - gesGenGuideMapTime;
00248                         printf("time spent in GES GenGuideMap [%.2fs] \n", gesGenGuideMapTime);
00249                 }
00250 
00251                 void PBSolverBeginOneTrial()
00252                 {
00253                         gesTrialTime = solvingTimer.elapsed();
00254                 }
00255 
00256                 void saveIntermediatePolicy();
00257 
00258                 void PBSolverFinishOneTrial();
00259 
00260                 bool PBSolverShouldStop(double ub, double lb)
00261                 {
00262                         bool stop = false;
00263                         if(userTerminatedG)
00264                         {
00265                                 stop = true;
00266                         }
00267 
00268                         
00269                         if ((ub-lb) < pbSolver->solverParams->targetPrecision)
00270                         {      
00271                                 printf("Target precision reached: %f (%f)\n\n", ub-lb, pbSolver->solverParams->targetPrecision);
00272                                 stop = true;
00273                         }
00274 
00275 
00276                         if(pbSolver->solverParams->timeoutSeconds > 0)
00277                         {
00278                                 if(solvingTimer.elapsed() > pbSolver->solverParams->timeoutSeconds )
00279                                 {
00280                                         printf("Preset timeout reached %f (%fs)\n\n", solvingTimer.elapsed(), pbSolver->solverParams->timeoutSeconds);
00281                                         stop = true;
00282                                 }
00283                         }
00284                         return stop;
00285                 }
00286 
00287                 void PBSolverPreSavePolicy()
00288                 {
00289                         printf("Total time spent in Solving (everything included)[%.2fs] \n", solvingTimer.elapsed());
00290                         printf("... writing policy to '%s'\n", pbSolver->solverParams->outPolicyFileName.c_str());
00291                 }
00292                 void PBSolverPostSavePolicy()
00293                 {
00294 
00295                 }
00296                 void PBSolver()
00297                 {
00298                 }
00299 
00300 
00301                 void PBPreGESUpdGuideMap()
00302                 {
00303                         updGuideMapStartTime = solvingTimer.elapsed();
00304                 }
00305 
00306                 void PBPostGESUpdGuideMap()
00307                 {
00308                         totUpdGuideMapTime += (solvingTimer.elapsed() - updGuideMapStartTime);
00309                 }
00310 
00311                 void Benchmark();
00312         };
00313 };
00314 
00315 #endif


appl
Author(s): petercai
autogenerated on Tue Jan 7 2014 11:02:29