$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 #ifndef __ENVIRONMENT_ROBARM_H_ 00030 #define __ENVIRONMENT_ROBARM_H_ 00031 00032 00033 00034 #define NUMOFLINKS 6 00035 00036 00037 #define ROBARM_LONGACTIONDIST_CELLS 30 //for R* max. distance in coord to a sample point. It should be exactly this, for one of the coordinates and this or smaller for the rest 00038 #define ROBARM_NUMOFRANDSUCCSATDIST 10 //# of random successors at distance defined above, used by R* search 00039 00040 //if cleared then the intersection of the whole arm against obstacles 00041 //and bounds is checked 00042 #define ENDEFF_CHECK_ONLY 0 00043 00044 #define UNIFORM_COST 1 //all the actions have the same costs when set 00045 00046 00047 #define INVALID_NUMBER 999 00048 00049 00050 typedef struct 00051 { 00052 short unsigned int x; 00053 short unsigned int y; 00054 bool bIsObstacle; 00055 }CELLV; 00056 00057 00058 //state structure 00059 typedef struct STATE2D_t 00060 { 00061 unsigned int g; 00062 short unsigned int iterationclosed; 00063 short unsigned int x; 00064 short unsigned int y; 00065 } State2D; 00066 00067 00068 typedef struct ENV_ROBARM_CONFIG 00069 { 00070 double EnvWidth_m; 00071 double EnvHeight_m; 00072 int EnvWidth_c; 00073 int EnvHeight_c; 00074 int BaseX_c; 00075 short unsigned int EndEffGoalX_c; 00076 short unsigned int EndEffGoalY_c; 00077 double LinkLength_m[NUMOFLINKS]; 00078 double LinkStartAngles_d[NUMOFLINKS]; 00079 double LinkGoalAngles_d[NUMOFLINKS]; 00080 char** Grid2D; 00081 double GridCellWidth; 00082 00083 double angledelta[NUMOFLINKS]; 00084 int anglevals[NUMOFLINKS]; 00085 00086 } EnvROBARMConfig_t; 00087 00088 00089 00090 typedef struct ENVROBARMHASHENTRY 00091 { 00092 int stateID; 00093 //state coordinates 00094 short unsigned int coord[NUMOFLINKS]; 00095 short unsigned int endeffx; 00096 short unsigned int endeffy; 00097 } EnvROBARMHashEntry_t; 00098 00099 00100 typedef struct 00101 { 00102 EnvROBARMHashEntry_t* goalHashEntry; 00103 EnvROBARMHashEntry_t* startHashEntry; 00104 00105 //Maps from coords to stateId 00106 int HashTableSize; 00107 vector<EnvROBARMHashEntry_t*>* Coord2StateIDHashTable; 00108 00109 //vector that maps from stateID to coords 00110 vector<EnvROBARMHashEntry_t*> StateID2CoordTable; 00111 00112 //any additional variables 00113 int** Heur; //h[fromx][fromy][tox][toy] = Heur[to][from], where to= tox+toy*width_c, from = fromx+fromy*width_c 00114 00115 }EnvironmentROBARM_t; 00116 00119 class EnvironmentROBARM : public DiscreteSpaceInformation 00120 { 00121 00122 public: 00123 00126 bool InitializeEnv(const char* sEnvFile); 00127 00130 bool InitializeMDPCfg(MDPConfig *MDPCfg); 00131 00134 int GetFromToHeuristic(int FromStateID, int ToStateID); 00137 int GetGoalHeuristic(int stateID); 00140 int GetStartHeuristic(int stateID); 00143 void SetAllActionsandAllOutcomes(CMDPSTATE* state); 00146 void SetAllPreds(CMDPSTATE* state); 00149 void GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV); 00152 void GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* CostV); 00153 00156 int SizeofCreatedEnv(); 00159 void PrintState(int stateID, bool bVerbose, FILE* fOut=NULL); 00162 void PrintEnv_Config(FILE* fOut); 00163 00164 00165 ~EnvironmentROBARM(){}; 00168 void PrintTimeStat(FILE* fOut); 00169 00170 private: 00171 00172 //member data 00173 EnvROBARMConfig_t EnvROBARMCfg; 00174 EnvironmentROBARM_t EnvROBARM; 00175 00176 00177 00178 void ComputeContAngles(short unsigned int coord[NUMOFLINKS], double angle[NUMOFLINKS]); 00179 void ComputeCoord(double angle[NUMOFLINKS], short unsigned int coord[NUMOFLINKS]); 00180 int ComputeEndEffectorPos(double angles[NUMOFLINKS], short unsigned int* pX, short unsigned int* pY); 00181 int IsValidCoord(short unsigned int coord[NUMOFLINKS], char** Grid2D=NULL, vector<CELLV>* pTestedCells=NULL); 00182 int distanceincoord(unsigned short* statecoord1, unsigned short* statecoord2); 00183 void ReInitializeState2D(State2D* state); 00184 void InitializeState2D(State2D* state, short unsigned int x, short unsigned int y); 00185 void Search2DwithQueue(State2D** statespace, int* HeurGrid, int searchstartx, int searchstarty); 00186 void Create2DStateSpace(State2D*** statespace2D); 00187 void Delete2DStateSpace(State2D*** statespace2D); 00188 void printangles(FILE* fOut, short unsigned int* coord, bool bGoal, bool bVerbose, bool bLocal); 00189 void DiscretizeAngles(); 00190 void Cell2ContXY(int x, int y, double *pX, double *pY); 00191 void ContXY2Cell(double x, double y, short unsigned int* pX, short unsigned int *pY); 00192 int IsValidLineSegment(double x0, double y0, double x1, double y1, char **Grid2D, 00193 vector<CELLV>* pTestedCells); 00194 void GetRandomSuccsatDistance(int SourceStateID, std::vector<int>* SuccIDV, std::vector<int>* CLowV); 00195 unsigned int GetHeurBasedonCoord(short unsigned int coord[NUMOFLINKS]); 00196 void PrintHeader(FILE* fOut); 00197 int cost(short unsigned int state1coord[], short unsigned int state2coord[]); 00198 00199 00200 00201 00202 void ReadConfiguration(FILE* fCfg); 00203 00204 void InitializeEnvConfig(); 00205 00206 unsigned int GETHASHBIN(short unsigned int* coord, int numofcoord); 00207 00208 void PrintHashTableHist(); 00209 00210 00211 EnvROBARMHashEntry_t* GetHashEntry(short unsigned int* coord, int numofcoord, bool bIsGoal); 00212 00213 EnvROBARMHashEntry_t* CreateNewHashEntry(short unsigned int* coord, int numofcoord, short unsigned int endeffx, short unsigned int endeffy); 00214 00215 00216 void CreateStartandGoalStates(); 00217 00218 bool InitializeEnvironment(); 00219 00220 void ComputeHeuristicValues(); 00221 00222 bool IsValidCell(int X, int Y); 00223 00224 bool IsWithinMapCell(int X, int Y); 00225 00226 00227 int GetEdgeCost(int FromStateID, int ToStateID); 00228 int GetRandomState(); 00229 bool AreEquivalent(int State1ID, int State2ID); 00230 00231 void PrintSuccGoal(int SourceStateID, int costtogoal, bool bVerbose, bool bLocal /*=false*/, FILE* fOut /*=NULL*/); 00232 00233 00234 }; 00235 00236 00237 00238 00239 00240 00241 00242 #endif 00243