$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_NAVXYTHETACARTLAT_H_ 00030 #define __ENVIRONMENT_NAVXYTHETACARTLAT_H_ 00031 00032 00033 //eight-connected grid 00034 #define NAVXYTHETACARTLAT_DXYWIDTH 8 00035 00036 #define ENVNAVXYTHETACARTLAT_DEFAULTOBSTHRESH 254 //see explanation of the value below 00037 00038 #define SBPL_XYTHETACARTLAT_MAXSTATESFORLOOKUP 100000000 //maximum number of states for storing them into lookup (as opposed to hash) 00039 00040 //definition of theta orientations 00041 //0 - is aligned with X-axis in the positive direction (1,0 in polar coordinates) 00042 //theta increases as we go counterclockwise 00043 //number of theta values - should be power of 2 00044 #define NAVXYTHETACARTLAT_THETADIRS 16 00045 00046 // TODO - ContTheta2Disc 00047 #define CART_THETADIRS 5 //Should be symmetric 00048 #define MAX_CART_ANGLE M_PI/4.0 00049 00050 //number of actions per x,y,theta state 00051 #define NAVXYTHETACARTLAT_DEFAULT_ACTIONWIDTH 5 //decrease, increase, same angle while moving plus decrease, increase angle while standing. 00052 00053 #define NAVXYTHETACARTLAT_COSTMULT_MTOMM 1000 00054 00055 typedef struct{ 00056 double x; 00057 double y; 00058 } EnvNAVXYTHETACARTLAT2Dpt_t; 00059 00060 typedef struct{ 00061 double x; 00062 double y; 00063 double theta; 00064 double cartangle; 00065 } EnvNAVXYTHETACARTLAT3Dpt_t; 00066 00067 00068 typedef struct EnvNAVXYTHETACARTLAT3DCELL{ 00069 int x; 00070 int y; 00071 int theta; 00072 int iteration; 00073 int cartangle; 00074 public: 00075 bool operator == (EnvNAVXYTHETACARTLAT3DCELL cell) {return (x==cell.x && y==cell.y && theta==cell.theta && cartangle == cell.cartangle);} 00076 } EnvNAVXYTHETACARTLAT3Dcell_t; 00077 00078 00079 typedef struct 00080 { 00081 char starttheta; 00082 char dX; 00083 char dY; 00084 char endtheta; 00085 char startcartangle; 00086 char endcartangle; 00087 unsigned int cost; 00088 vector<sbpl_2Dcell_t> intersectingcellsV; 00089 //start at 0,0,starttheta and end at endcell in continuous domain with half-bin less to account for 0,0 start 00090 vector<EnvNAVXYTHETACARTLAT3Dpt_t> intermptV; 00091 //start at 0,0,starttheta and end at endcell in discrete domain 00092 vector<EnvNAVXYTHETACARTLAT3Dcell_t> interm3DcellsV; 00093 } EnvNAVXYTHETACARTLATAction_t; 00094 00095 00096 typedef struct 00097 { 00098 int stateID; 00099 int X; 00100 int Y; 00101 char Theta; 00102 char CartAngle; 00103 int iteration; 00104 } EnvNAVXYTHETACARTLATHashEntry_t; 00105 00106 00107 typedef struct 00108 { 00109 int motprimID; 00110 unsigned char starttheta_c; 00111 int additionalactioncostmult; 00112 EnvNAVXYTHETACARTLAT3Dcell_t endcell; 00113 //intermptV start at 0,0,starttheta and end at endcell in continuous domain with half-bin less to account for 0,0 start 00114 vector<EnvNAVXYTHETACARTLAT3Dpt_t> intermptV; 00115 }SBPL_xythetacart_mprimitive; 00116 00117 00118 //variables that dynamically change (e.g., array of states, ...) 00119 typedef struct 00120 { 00121 00122 int startstateid; 00123 int goalstateid; 00124 00125 bool bInitialized; 00126 00127 //any additional variables 00128 00129 00130 }EnvironmentNAVXYTHETACARTLAT_t; 00131 00132 //configuration parameters 00133 typedef struct ENV_NAVXYTHETACARTLAT_CONFIG 00134 { 00135 int EnvWidth_c; 00136 int EnvHeight_c; 00137 int StartX_c; 00138 int StartY_c; 00139 int StartTheta; 00140 int StartCartAngle; 00141 int EndX_c; 00142 int EndY_c; 00143 int EndTheta; 00144 int EndCartAngle; 00145 unsigned char** Grid2D; 00146 00147 //the value at which and above which cells are obstacles in the maps sent from outside 00148 //the default is defined above 00149 unsigned char obsthresh; 00150 00151 //the value at which and above which until obsthresh (not including it) cells have the nearest obstacle at distance smaller than or equal to 00152 //the inner circle of the robot. In other words, the robot is definitely colliding with the obstacle, independently of its orientation 00153 //if no such cost is known, then it should be set to obsthresh (if center of the robot collides with obstacle, then the whole robot collides with it 00154 //independently of its rotation) 00155 unsigned char cost_inscribed_thresh; 00156 00157 //the value at which and above which until cost_inscribed_thresh (not including it) cells 00158 //**may** have a nearest osbtacle within the distance that is in between the robot inner circle and the robot outer circle 00159 //any cost below this value means that the robot will NOT collide with any obstacle, independently of its orientation 00160 //if no such cost is known, then it should be set to 0 or -1 (then no cell cost will lower than it, and therefore the robot's footprint will always be checked) 00161 int cost_possibly_circumscribed_thresh; //it has to be integer, because -1 means that it is not provided. 00162 00163 double nominalvel_mpersecs; 00164 double timetoturn45degsinplace_secs; 00165 double cellsize_m; 00166 00167 int dXY[NAVXYTHETACARTLAT_DXYWIDTH][2]; 00168 00169 EnvNAVXYTHETACARTLATAction_t** ActionsV; //array of actions, ActionsV[i][j] - jth action for sourcetheta = i 00170 vector<EnvNAVXYTHETACARTLATAction_t*>* PredActionsV; //PredActionsV[i] - vector of pointers to the actions that result in a state with theta = i 00171 00172 int actionwidth; //number of motion primitives 00173 vector<SBPL_xythetacart_mprimitive> mprimV; 00174 00175 vector<sbpl_2Dpt_t> FootprintPolygon; 00176 vector<sbpl_2Dpt_t> CartPolygon; 00177 sbpl_2Dpt_t CartOffset; 00178 sbpl_2Dpt_t CartCenterOffset; 00179 } EnvNAVXYTHETACARTLATConfig_t; 00180 00181 00182 00183 class SBPL2DGridSearch; 00184 00189 class EnvironmentNAVXYTHETACARTLATTICE : public DiscreteSpaceInformation 00190 { 00191 00192 public: 00193 00194 EnvironmentNAVXYTHETACARTLATTICE(); 00195 00203 // TODO - add cart perimeters and offset 00204 bool InitializeEnv(const char* sEnvFile, const vector<sbpl_2Dpt_t>& perimeterptsV, const vector<sbpl_2Dpt_t>& cartperimeterptsV, sbpl_2Dpt_t &cart_offset, const char* sMotPrimFile); 00208 bool InitializeEnv(const char* sEnvFile); 00212 virtual bool SetEnvParameter(const char* parameter, int value); 00216 virtual int GetEnvParameter(const char* parameter); 00220 bool InitializeMDPCfg(MDPConfig *MDPCfg); 00224 virtual int GetFromToHeuristic(int FromStateID, int ToStateID) = 0; 00228 virtual int GetGoalHeuristic(int stateID) = 0; 00232 virtual int GetStartHeuristic(int stateID) = 0; 00236 virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state) = 0; 00240 virtual void SetAllPreds(CMDPSTATE* state); 00244 virtual void GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV); 00248 virtual void GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* CostV) = 0; 00249 00253 virtual void EnsureHeuristicsUpdated(bool bGoalHeuristics); 00254 00258 void PrintEnv_Config(FILE* fOut); 00259 00277 bool InitializeEnv(int width, int height, 00279 const unsigned char* mapdata, 00280 double startx, double starty, double starttheta, double startcartangle, 00281 double goalx, double goaly, double goaltheta, double goalcartangle, 00282 double goaltol_x, double goaltol_y, double goaltol_theta, double goaltol_cartangle, 00283 const vector<sbpl_2Dpt_t> & perimeterptsV, 00284 const sbpl_2Dpt_t & cart_offset, 00285 const vector<sbpl_2Dpt_t> & cartptsV, 00286 double cellsize_m, double nominalvel_mpersecs, double timetoturn45degsinplace_secs, 00287 unsigned char obsthresh, const char* sMotPrimFile); 00291 bool UpdateCost(int x, int y, unsigned char newcost); 00297 virtual void GetPredsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *preds_of_changededgesIDV) = 0; 00301 virtual void GetSuccsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *succs_of_changededgesIDV) = 0; 00302 00306 bool IsObstacle(int x, int y); 00311 bool IsValidConfiguration(int X, int Y, int Theta, int CartAngle); 00312 00316 // TODO - add cart parameters 00317 void GetEnvParms(int *size_x, int *size_y, 00318 double* startx, double* starty, double*starttheta, double*startcartangle, 00319 double* goalx, double* goaly, double* goaltheta, double*goalcartangle, 00320 double* cellsize_m, double* nominalvel_mpersecs, 00321 double* timetoturn45degsinplace_secs, unsigned char* obsthresh, 00322 vector<SBPL_xythetacart_mprimitive>* mprimitiveV); 00323 00327 const EnvNAVXYTHETACARTLATConfig_t* GetEnvNavConfig(); 00328 00329 00330 virtual ~EnvironmentNAVXYTHETACARTLATTICE(); 00334 void PrintTimeStat(FILE* fOut); 00338 unsigned char GetMapCost(int x, int y); 00339 00343 bool IsWithinMapCell(int X, int Y); 00344 00345 00348 virtual void PrintVars(){}; 00349 00350 bool initialized_; 00351 00352 protected: 00353 00354 virtual int GetActionCost(int SourceX, int SourceY, int SourceTheta, int SourceCartAngle, EnvNAVXYTHETACARTLATAction_t* action); 00355 00356 00357 //member data 00358 EnvNAVXYTHETACARTLATConfig_t EnvNAVXYTHETACARTLATCfg; 00359 EnvironmentNAVXYTHETACARTLAT_t EnvNAVXYTHETACARTLAT; 00360 vector<EnvNAVXYTHETACARTLAT3Dcell_t> affectedsuccstatesV; //arrays of states whose outgoing actions cross cell 0,0 00361 vector<EnvNAVXYTHETACARTLAT3Dcell_t> affectedpredstatesV; //arrays of states whose incoming actions cross cell 0,0 00362 int iteration; 00363 00364 //2D search for heuristic computations 00365 bool bNeedtoRecomputeStartHeuristics; //set whenever grid2Dsearchfromstart needs to be re-executed 00366 bool bNeedtoRecomputeGoalHeuristics; //set whenever grid2Dsearchfromgoal needs to be re-executed 00367 SBPL2DGridSearch* grid2Dsearchfromstart; //computes h-values that estimate distances from start x,y to all cells 00368 SBPL2DGridSearch* grid2Dsearchfromgoal; //computes h-values that estimate distances to goal x,y from all cells 00369 00370 virtual void ReadConfiguration(FILE* fCfg); 00371 00372 void InitializeEnvConfig(vector<SBPL_xythetacart_mprimitive>* motionprimitiveV); 00373 00374 00375 bool CheckQuant(FILE* fOut); 00376 00377 void SetConfiguration(int width, int height, 00379 const unsigned char* mapdata, 00380 int startx, int starty, int starttheta, int startcartangle, 00381 int goalx, int goaly, int goaltheta, int goalcartangle, 00382 double cellsize_m, double nominalvel_mpersecs, 00383 double timetoturn45degsinplace_secs, 00384 const vector<sbpl_2Dpt_t> & robot_perimeterV, 00385 const vector<sbpl_2Dpt_t> & cart_perimeterV, 00386 const sbpl_2Dpt_t &cart_offset); 00387 00388 bool InitGeneral( vector<SBPL_xythetacart_mprimitive>* motionprimitiveV); 00389 void PrecomputeActionswithBaseMotionPrimitive(vector<SBPL_xythetacart_mprimitive>* motionprimitiveV); 00390 void PrecomputeActionswithCompleteMotionPrimitive(vector<SBPL_xythetacart_mprimitive>* motionprimitiveV); 00391 void PrecomputeActions(); 00392 00393 void CreateStartandGoalStates(); 00394 00395 virtual void InitializeEnvironment() = 0; 00396 00397 void ComputeHeuristicValues(); 00398 00399 bool IsValidCell(int X, int Y); 00400 00401 void CalculateFootprintForPose(EnvNAVXYTHETACARTLAT3Dpt_t pose, vector<sbpl_2Dcell_t>* footprint); 00402 void RemoveSourceFootprint(EnvNAVXYTHETACARTLAT3Dpt_t sourcepose, vector<sbpl_2Dcell_t>* footprint); 00403 00404 virtual void GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV, vector<EnvNAVXYTHETACARTLATAction_t*>* actionindV=NULL) = 0; 00405 00406 double EuclideanDistance_m(int X1, int Y1, int X2, int Y2); 00407 00408 void ComputeReplanningData(); 00409 void ComputeReplanningDataforAction(EnvNAVXYTHETACARTLATAction_t* action); 00410 00411 bool ReadMotionPrimitives(FILE* fMotPrims); 00412 bool ReadinMotionPrimitive(SBPL_xythetacart_mprimitive* pMotPrim, FILE* fIn); 00413 bool ReadinCell(EnvNAVXYTHETACARTLAT3Dcell_t* cell, FILE* fIn); 00414 bool ReadinPose(EnvNAVXYTHETACARTLAT3Dpt_t* pose, FILE* fIn); 00415 00416 void PrintHeuristicValues(); 00417 void PrintFootprint(); 00418 EnvNAVXYTHETACARTLAT3Dpt_t getCartCenter(EnvNAVXYTHETACARTLAT3Dpt_t pose, sbpl_2Dpt_t cart_center_offset); 00419 00420 }; 00421 00422 00423 class EnvironmentNAVXYTHETACARTLAT : public EnvironmentNAVXYTHETACARTLATTICE 00424 { 00425 00426 public: 00427 EnvironmentNAVXYTHETACARTLAT() 00428 { 00429 HashTableSize = 0; 00430 Coord2StateIDHashTable = NULL; 00431 Coord2StateIDHashTable_lookup = NULL; 00432 }; 00433 00434 ~EnvironmentNAVXYTHETACARTLAT(); 00435 00438 int SetStart(double x, double y, double theta, double cartangle); 00441 int SetGoal(double x, double y, double theta, double cartangle); 00444 void SetGoalTolerance(double tol_x, double tol_y, double tol_theta, double tol_cartangle) { } 00447 void GetCoordFromState(int stateID, int& x, int& y, int& theta, int& cartangle) const; 00450 int GetStateFromCoord(int x, int y, int theta, int cartangle); 00451 00455 bool ConvertStateIDPathintoXYThetaPath(vector<int>* stateIDPath, vector<EnvNAVXYTHETACARTLAT3Dpt_t>* xythetaPath); 00458 void PrintState(int stateID, bool bVerbose, FILE* fOut=NULL); 00461 virtual void GetPreds(int TargetStateID, vector<int>* PredIDV, vector<int>* CostV); 00465 virtual void GetSuccs(int SourceStateID, vector<int>* SuccIDV, vector<int>* CostV, vector<EnvNAVXYTHETACARTLATAction_t*>* actionindV=NULL); 00466 00471 void GetPredsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *preds_of_changededgesIDV); 00474 void GetSuccsofChangedEdges(vector<nav2dcell_t> const * changedcellsV, vector<int> *succs_of_changededgesIDV); 00475 00478 virtual void SetAllActionsandAllOutcomes(CMDPSTATE* state); 00479 00482 virtual int GetFromToHeuristic(int FromStateID, int ToStateID); 00485 virtual int GetGoalHeuristic(int stateID); 00488 virtual int GetStartHeuristic(int stateID); 00489 00492 virtual int SizeofCreatedEnv(); 00495 virtual void PrintVars(){}; 00496 00497 protected: 00498 00499 //hash table of size x_size*y_size. Maps from coords to stateId 00500 int HashTableSize; 00501 vector<EnvNAVXYTHETACARTLATHashEntry_t*>* Coord2StateIDHashTable; 00502 //vector that maps from stateID to coords 00503 vector<EnvNAVXYTHETACARTLATHashEntry_t*> StateID2CoordTable; 00504 00505 EnvNAVXYTHETACARTLATHashEntry_t** Coord2StateIDHashTable_lookup; 00506 00507 unsigned int GETHASHBIN(unsigned int X, unsigned int Y, unsigned int Theta, unsigned int CartAngle); 00508 00509 EnvNAVXYTHETACARTLATHashEntry_t* GetHashEntry_hash(int X, int Y, int Theta, int CartAngle); 00510 EnvNAVXYTHETACARTLATHashEntry_t* CreateNewHashEntry_hash(int X, int Y, int Theta, int CartAngle); 00511 EnvNAVXYTHETACARTLATHashEntry_t* GetHashEntry_lookup(int X, int Y, int Theta, int CartAngle); 00512 EnvNAVXYTHETACARTLATHashEntry_t* CreateNewHashEntry_lookup(int X, int Y, int Theta, int CartAngle); 00513 00514 //pointers to functions 00515 EnvNAVXYTHETACARTLATHashEntry_t* (EnvironmentNAVXYTHETACARTLAT::*GetHashEntry)(int X, int Y, int Theta, int CartAngle); 00516 EnvNAVXYTHETACARTLATHashEntry_t* (EnvironmentNAVXYTHETACARTLAT::*CreateNewHashEntry)(int X, int Y, int Theta, int CartAngle); 00517 00518 00519 virtual void InitializeEnvironment(); 00520 00521 void PrintHashTableHist(FILE* fOut); 00522 00523 00524 }; 00525 00526 00527 #endif 00528