$search
00001 /* 00002 * Copyright (c) 2009, 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 #ifndef __ENVIRONMENT_NAV2DUU_H_ 00030 #define __ENVIRONMENT_NAV2DUU_H_ 00031 00032 #define ENVNAV2DUU_COSTMULT 1000 00033 00034 #define NAV2DUU_MAXACTIONSWIDTH 9 00035 00036 #define ENVNAV2DUU_MAXDIRS 8 00037 00038 typedef struct ENV_NAV2DUU_CONFIG 00039 { 00040 //parameters that are read from the configuration file 00041 int EnvWidth_c; 00042 int EnvHeight_c; 00043 int StartX_c; 00044 int StartY_c; 00045 int EndX_c; 00046 int EndY_c; 00047 //cost matrix 00048 unsigned char** Grid2D; 00049 //the value at which and above which cells are obstacles in the maps sent from outside 00050 //the default is defined above 00051 unsigned char obsthresh; 00052 //uncertainty matrix (0 defines P(obstacle) = 0, and 1.0 defines P(obstacle) = 1) 00053 float** UncertaintyGrid2D; 00054 //matrix of hidden variable IDs 00055 int** HiddenVariableXY2ID; 00056 00057 //derived and initialized elsewhere parameters 00058 00059 //possible transitions 00060 int dx_[ENVNAV2DUU_MAXDIRS]; 00061 int dy_[ENVNAV2DUU_MAXDIRS]; 00062 //distances of transitions 00063 int dxy_distance_mm_[ENVNAV2DUU_MAXDIRS]; 00064 //the intermediate cells through which the actions go 00065 int dxintersects_[ENVNAV2D_MAXDIRS][2]; 00066 int dyintersects_[ENVNAV2D_MAXDIRS][2]; 00067 int numofdirs; //for now can only be 8 00068 00069 //size of environment, number of hidden variables 00070 int sizeofS; 00071 int sizeofH; 00072 00073 } EnvNAV2DUUConfig_t; 00074 00075 #define NAVNAV2DUU_MAXWIDTHHEIGH 1024 00076 #define ENVNAV2DUU_STATEIDTOY(stateID) (stateID%NAVNAV2DUU_MAXWIDTHHEIGH) 00077 #define ENVNAV2DUU_STATEIDTOX(stateID) (stateID/NAVNAV2DUU_MAXWIDTHHEIGH) 00078 #define ENVNAV2DUU_XYTOSTATEID(X, Y) (X*NAVNAV2DUU_MAXWIDTHHEIGH + Y) 00079 00080 00081 typedef struct 00082 { 00083 00084 int startstateid; 00085 int goalstateid; 00086 00087 00088 //any additional variables 00089 bool bInitialized; 00090 00091 }EnvironmentNAV2DUU_t; 00092 00093 00096 class EnvironmentNAV2DUU : public DiscreteSpaceInformation 00097 { 00098 00099 public: 00100 00103 bool InitializeEnv(const char* sEnvFile); 00104 00116 bool InitializeEnv(int width, int height, 00117 const unsigned char* mapdata, const float* uncertaintymapdata, unsigned char obsthresh); 00120 int SetStart(int x, int y); 00123 int SetGoal(int x, int y); 00126 bool UpdateCost(int x, int y, unsigned char newcost); 00127 00128 00131 bool InitializeMDPCfg(MDPConfig *MDPCfg); 00134 int GetFromToHeuristic(int FromStateID, int ToStateID); 00137 int GetGoalHeuristic(int stateID); 00140 int GetStartHeuristic(int stateID); 00141 00144 void PrintState(int stateID, bool bVerbose, FILE* fOut=NULL); 00147 void PrintEnv_Config(FILE* fOut); 00148 00149 00150 EnvironmentNAV2DUU(); 00151 ~EnvironmentNAV2DUU(){}; 00152 00155 void GetPreds(int stateID, const vector<sbpl_BinaryHiddenVar_t>* updatedhvaluesV, vector<CMDPACTION>* IncomingDetActionV, 00156 vector<CMDPACTION>* IncomingStochActionV, vector<sbpl_BinaryHiddenVar_t>* StochActionNonpreferredOutcomeV); 00157 00158 00161 void SetAllActionsandAllOutcomes(CMDPSTATE* state){ 00162 SBPL_ERROR("ERROR: SetAllActionsandAllOutcomes not supported in NAV2D UNDER UNCERTAINTY\n"); 00163 throw new SBPL_Exception(); 00164 }; 00167 void SetAllPreds(CMDPSTATE* state){ 00168 SBPL_ERROR("ERROR: SetAllPreds not supported in NAV2D UNDER UNCERTAINTY\n"); 00169 throw new SBPL_Exception(); 00170 }; 00173 void GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV){ 00174 SBPL_ERROR("ERROR: GetSuccs not supported in NAV2D UNDER UNCERTAINTY\n"); 00175 throw new SBPL_Exception(); 00176 }; 00179 void GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* CostV){ 00180 SBPL_ERROR("ERROR: GetPreds not supported in NAV2D UNDER UNCERTAINTY\n"); 00181 throw new SBPL_Exception(); 00182 }; 00183 00186 int SizeofCreatedEnv(); 00189 int SizeofH(); 00190 00191 00192 00193 private: 00194 00195 //member variables 00196 EnvNAV2DUUConfig_t EnvNAV2DUUCfg; 00197 EnvironmentNAV2DUU_t EnvNAV2DUU; 00198 00199 00200 //mapdata and uncertaintymapdata is assumed to be organized into a linear array with y being major: map[x+y*width] 00201 void SetConfiguration(int width, int height, const unsigned char* mapdata, const float* uncertaintymapdata); 00202 00203 void ReadConfiguration(FILE* fCfg); 00204 void InitializeEnvConfig(); 00205 void InitializeEnvironment(); 00206 void ComputeHeuristicValues(); 00207 bool InitGeneral(); 00208 00209 bool IsValidRobotPosition(int X, int Y); 00210 bool IsWithinMapCell(int X, int Y); 00211 00212 void Computedxy(); 00213 00214 00215 }; 00216 00217 00218 #endif 00219