Public Member Functions | Private Member Functions | Private Attributes
EnvironmentNAV2D Class Reference

2D (x,y) grid planning problem. For general structure see comments on parent class DiscreteSpaceInformation More...

#include <environment_nav2D.h>

Inheritance diagram for EnvironmentNAV2D:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool AreEquivalent (int StateID1, int StateID2)
 returns true if two states meet the same condition - see environment.h for more info
 EnvironmentNAV2D ()
void GetCoordFromState (int stateID, int &x, int &y) const
 returns the actual <x,y> associated with state of stateID
const EnvNAV2DConfig_tGetEnvNavConfig ()
 access to internal configuration data structure
void GetEnvParms (int *size_x, int *size_y, int *startx, int *starty, int *goalx, int *goaly, unsigned char *obsthresh)
 returns the parameters associated with the current environment. This is useful for setting up a copy of an environment (i.e., second planning problem)
int GetFromToHeuristic (int FromStateID, int ToStateID)
 see comments on the same function in the parent class
int GetGoalHeuristic (int stateID)
 see comments on the same function in the parent class
unsigned char GetMapCost (int x, int y)
 returns the cost associated with <x,y> cell, i.e., A[x][y]
void GetPreds (int TargetStateID, vector< int > *PredIDV, vector< int > *CostV)
 see comments on the same function in the parent class
void GetPredsofChangedEdges (vector< nav2dcell_t > const *changedcellsV, vector< int > *preds_of_changededgesIDV)
 this function fill in Predecessor/Successor states of edges whose costs changed It takes in an array of cells whose traversability changed, and returns (in vector preds_of_changededgesIDV) the IDs of all states that have outgoing edges that go through the changed cells
virtual void GetRandomNeighs (int stateID, std::vector< int > *NeighIDV, std::vector< int > *CLowV, int nNumofNeighs, int nDist_c, bool bSuccs)
 generates nNumofNeighs random neighbors of cell <X,Y> at distance nDist_c (measured in cells) it will also generate goal if within this distance as an additional neighbor
virtual void GetRandomPredsatDistance (int TargetStateID, std::vector< int > *PredIDV, std::vector< int > *CLowV)
 generates preds at some domain-dependent distance - see environment.h for more info used by certain searches such as R*
virtual void GetRandomSuccsatDistance (int SourceStateID, std::vector< int > *SuccIDV, std::vector< int > *CLowV)
 generates succs at some domain-dependent distance - see environment.h for more info used by certain searches such as R*
int GetStartHeuristic (int stateID)
 see comments on the same function in the parent class
int GetStateFromCoord (int x, int y)
 returns a stateID associated with coordinates <x,y>
void GetSuccs (int SourceStateID, vector< int > *SuccIDV, vector< int > *CostV)
 see comments on the same function in the parent class
void GetSuccsofChangedEdges (vector< nav2dcell_t > const *changedcellsV, vector< int > *succs_of_changededgesIDV)
 same as GetPredsofChangedEdges, but returns successor states. Both functions need to be present for incremental search
bool InitGeneral ()
 performs initialization of environments. It is usually called in from InitializeEnv. But if SetConfiguration is used, then one should call InitGeneral by himself
bool InitializeEnv (const char *sEnvFile)
 see comments on the same function in the parent class
bool InitializeEnv (int width, int height, const unsigned char *mapdata, int startx, int starty, int goalx, int goaly, unsigned char obsthresh)
 initialize environment. Gridworld is defined as matrix A of size width by height. So, internally, it is accessed as A[x][y] with x ranging from 0 to width-1 and and y from 0 to height-1 Each element in A[x][y] is unsigned char. A[x][y] = 0 corresponds to fully traversable and cost is just Euclidean distance The cost of transition between two neighboring cells is EuclideanDistance*(max(A[sourcex][sourcey],A[targetx][targety])+1) If A[x][y] >= obsthresh, then in the above equation it is assumed to be infinite. mapdata is a pointer to the values of A. If it is null, then A is initialized to all zeros. Mapping is: A[x][y] = mapdata[x+y*width] start/goal are given by startx, starty, goalx,goaly. If they are not known yet, just set them to 0. Later setgoal/setstart can be executed finally obsthresh defined obstacle threshold, as mentioned above
bool InitializeEnv (int width, int height, const unsigned char *mapdata, unsigned char obsthresh)
 a short version of environment initialization. Here start and goal coordinates will be set to 0s
bool InitializeMDPCfg (MDPConfig *MDPCfg)
 see comments on the same function in the parent class
bool IsObstacle (int x, int y)
 returns true if <x,y> is obstacle (used by the value of this cell and obsthresh)
bool IsWithinMapCell (int X, int Y)
 checks X,Y against map boundaries
void PrintEnv_Config (FILE *fOut)
 see comments on the same function in the parent class
void PrintState (int stateID, bool bVerbose, FILE *fOut=NULL)
 see comments on the same function in the parent class
void PrintTimeStat (FILE *fOut)
 print some time statistics
void SetAllActionsandAllOutcomes (CMDPSTATE *state)
 see comments on the same function in the parent class
void SetAllPreds (CMDPSTATE *state)
 see comments on the same function in the parent class
void SetConfiguration (int width, int height, const unsigned char *mapdata, int startx, int starty, int goalx, int goaly)
 a direct way to set the configuration of environment - see InitializeEnv function for details about the parameters it is not a full way to initialize environment. To fully initialize, one needs to executed InitGeneral in addition.
bool SetEnvParameter (const char *parameter, int value)
 way to set up various parameters. For a list of parameters, see the body of the function - it is pretty straightforward
int SetGoal (int x, int y)
 set goal location
void SetGoalTolerance (double tol_x, double tol_y, double tol_theta)
 currently, this is not used
int SetStart (int x, int y)
 set start location
int SizeofCreatedEnv ()
 see comments on the same function in the parent class
bool UpdateCost (int x, int y, unsigned char newcost)
 update the traversability of a cell<x,y>
 ~EnvironmentNAV2D ()

Private Member Functions

void Computedxy ()
void ComputeHeuristicValues ()
EnvNAV2DHashEntry_tCreateNewHashEntry (int X, int Y)
void CreateStartandGoalStates ()
unsigned int GETHASHBIN (unsigned int X, unsigned int Y)
EnvNAV2DHashEntry_tGetHashEntry (int X, int Y)
void InitializeEnvConfig ()
void InitializeEnvironment ()
bool IsValidCell (int X, int Y)
void PrintHashTableHist ()
void ReadConfiguration (FILE *fCfg)

Private Attributes

EnvironmentNAV2D_t EnvNAV2D
EnvNAV2DConfig_t EnvNAV2DCfg

Detailed Description

2D (x,y) grid planning problem. For general structure see comments on parent class DiscreteSpaceInformation

Definition at line 105 of file environment_nav2D.h.


Constructor & Destructor Documentation

Definition at line 46 of file environment_nav2D.cpp.

Definition at line 454 of file environment_nav2D.cpp.


Member Function Documentation

bool EnvironmentNAV2D::AreEquivalent ( int  StateID1,
int  StateID2 
) [virtual]

returns true if two states meet the same condition - see environment.h for more info

Reimplemented from DiscreteSpaceInformation.

Definition at line 1289 of file environment_nav2D.cpp.

void EnvironmentNAV2D::Computedxy ( ) [private]

Definition at line 312 of file environment_nav2D.cpp.

Definition at line 619 of file environment_nav2D.cpp.

EnvNAV2DHashEntry_t * EnvironmentNAV2D::CreateNewHashEntry ( int  X,
int  Y 
) [private]

Definition at line 393 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetCoordFromState ( int  stateID,
int &  x,
int &  y 
) const

returns the actual <x,y> associated with state of stateID

Definition at line 1073 of file environment_nav2D.cpp.

access to internal configuration data structure

Definition at line 1089 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetEnvParms ( int *  size_x,
int *  size_y,
int *  startx,
int *  starty,
int *  goalx,
int *  goaly,
unsigned char *  obsthresh 
)

returns the parameters associated with the current environment. This is useful for setting up a copy of an environment (i.e., second planning problem)

Definition at line 1247 of file environment_nav2D.cpp.

int EnvironmentNAV2D::GetFromToHeuristic ( int  FromStateID,
int  ToStateID 
) [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 705 of file environment_nav2D.cpp.

int EnvironmentNAV2D::GetGoalHeuristic ( int  stateID) [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 731 of file environment_nav2D.cpp.

unsigned int EnvironmentNAV2D::GETHASHBIN ( unsigned int  X,
unsigned int  Y 
) [private]

Definition at line 76 of file environment_nav2D.cpp.

EnvNAV2DHashEntry_t * EnvironmentNAV2D::GetHashEntry ( int  X,
int  Y 
) [private]

Definition at line 353 of file environment_nav2D.cpp.

unsigned char EnvironmentNAV2D::GetMapCost ( int  x,
int  y 
)

returns the cost associated with <x,y> cell, i.e., A[x][y]

Definition at line 1240 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetPreds ( int  TargetStateID,
vector< int > *  PredIDV,
vector< int > *  CostV 
)

see comments on the same function in the parent class

Definition at line 954 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetPredsofChangedEdges ( vector< nav2dcell_t > const *  changedcellsV,
vector< int > *  preds_of_changededgesIDV 
)

this function fill in Predecessor/Successor states of edges whose costs changed It takes in an array of cells whose traversability changed, and returns (in vector preds_of_changededgesIDV) the IDs of all states that have outgoing edges that go through the changed cells

Definition at line 1187 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetRandomNeighs ( int  stateID,
std::vector< int > *  NeighIDV,
std::vector< int > *  CLowV,
int  nNumofNeighs,
int  nDist_c,
bool  bSuccs 
) [virtual]

generates nNumofNeighs random neighbors of cell <X,Y> at distance nDist_c (measured in cells) it will also generate goal if within this distance as an additional neighbor

Definition at line 513 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetRandomPredsatDistance ( int  TargetStateID,
std::vector< int > *  PredIDV,
std::vector< int > *  CLowV 
) [virtual]

generates preds at some domain-dependent distance - see environment.h for more info used by certain searches such as R*

Reimplemented from DiscreteSpaceInformation.

Definition at line 1338 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetRandomSuccsatDistance ( int  SourceStateID,
std::vector< int > *  SuccIDV,
std::vector< int > *  CLowV 
) [virtual]

generates succs at some domain-dependent distance - see environment.h for more info used by certain searches such as R*

Reimplemented from DiscreteSpaceInformation.

Definition at line 1311 of file environment_nav2D.cpp.

int EnvironmentNAV2D::GetStartHeuristic ( int  stateID) [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 752 of file environment_nav2D.cpp.

int EnvironmentNAV2D::GetStateFromCoord ( int  x,
int  y 
)

returns a stateID associated with coordinates <x,y>

Definition at line 1079 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetSuccs ( int  SourceStateID,
vector< int > *  SuccIDV,
vector< int > *  CostV 
)

see comments on the same function in the parent class

Definition at line 877 of file environment_nav2D.cpp.

void EnvironmentNAV2D::GetSuccsofChangedEdges ( vector< nav2dcell_t > const *  changedcellsV,
vector< int > *  succs_of_changededgesIDV 
)

same as GetPredsofChangedEdges, but returns successor states. Both functions need to be present for incremental search

Definition at line 1212 of file environment_nav2D.cpp.

performs initialization of environments. It is usually called in from InitializeEnv. But if SetConfiguration is used, then one should call InitGeneral by himself

Definition at line 681 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::InitializeEnv ( const char *  sEnvFile) [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 631 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::InitializeEnv ( int  width,
int  height,
const unsigned char *  mapdata,
int  startx,
int  starty,
int  goalx,
int  goaly,
unsigned char  obsthresh 
)

initialize environment. Gridworld is defined as matrix A of size width by height. So, internally, it is accessed as A[x][y] with x ranging from 0 to width-1 and and y from 0 to height-1 Each element in A[x][y] is unsigned char. A[x][y] = 0 corresponds to fully traversable and cost is just Euclidean distance The cost of transition between two neighboring cells is EuclideanDistance*(max(A[sourcex][sourcey],A[targetx][targety])+1) If A[x][y] >= obsthresh, then in the above equation it is assumed to be infinite. mapdata is a pointer to the values of A. If it is null, then A is initialized to all zeros. Mapping is: A[x][y] = mapdata[x+y*width] start/goal are given by startx, starty, goalx,goaly. If they are not known yet, just set them to 0. Later setgoal/setstart can be executed finally obsthresh defined obstacle threshold, as mentioned above

Parameters:
mapdataif mapdata is NULL the grid is initialized to all freespace

Definition at line 659 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::InitializeEnv ( int  width,
int  height,
const unsigned char *  mapdata,
unsigned char  obsthresh 
)

a short version of environment initialization. Here start and goal coordinates will be set to 0s

Parameters:
mapdataif mapdata is NULL the grid is initialized to all freespace

Definition at line 649 of file environment_nav2D.cpp.

Definition at line 284 of file environment_nav2D.cpp.

Definition at line 474 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::InitializeMDPCfg ( MDPConfig MDPCfg) [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 694 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::IsObstacle ( int  x,
int  y 
)

returns true if <x,y> is obstacle (used by the value of this cell and obsthresh)

Definition at line 1233 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::IsValidCell ( int  X,
int  Y 
) [private]

Definition at line 439 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::IsWithinMapCell ( int  X,
int  Y 
)

checks X,Y against map boundaries

Definition at line 446 of file environment_nav2D.cpp.

void EnvironmentNAV2D::PrintEnv_Config ( FILE *  fOut) [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1166 of file environment_nav2D.cpp.

Definition at line 84 of file environment_nav2D.cpp.

void EnvironmentNAV2D::PrintState ( int  stateID,
bool  bVerbose,
FILE *  fOut = NULL 
) [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1046 of file environment_nav2D.cpp.

void EnvironmentNAV2D::PrintTimeStat ( FILE *  fOut)

print some time statistics

Definition at line 1176 of file environment_nav2D.cpp.

void EnvironmentNAV2D::ReadConfiguration ( FILE *  fCfg) [private]

Definition at line 157 of file environment_nav2D.cpp.

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 776 of file environment_nav2D.cpp.

void EnvironmentNAV2D::SetAllPreds ( CMDPSTATE state) [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 868 of file environment_nav2D.cpp.

void EnvironmentNAV2D::SetConfiguration ( int  width,
int  height,
const unsigned char *  mapdata,
int  startx,
int  starty,
int  goalx,
int  goaly 
)

a direct way to set the configuration of environment - see InitializeEnv function for details about the parameters it is not a full way to initialize environment. To fully initialize, one needs to executed InitGeneral in addition.

Parameters:
mapdataif mapdata is NULL the grid is initialized to all freespace

Definition at line 109 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::SetEnvParameter ( const char *  parameter,
int  value 
) [virtual]

way to set up various parameters. For a list of parameters, see the body of the function - it is pretty straightforward

Reimplemented from DiscreteSpaceInformation.

Definition at line 1260 of file environment_nav2D.cpp.

int EnvironmentNAV2D::SetGoal ( int  x,
int  y 
)

set goal location

Definition at line 1094 of file environment_nav2D.cpp.

void EnvironmentNAV2D::SetGoalTolerance ( double  tol_x,
double  tol_y,
double  tol_theta 
)

currently, this is not used

not used yet

Definition at line 1123 of file environment_nav2D.cpp.

int EnvironmentNAV2D::SetStart ( int  x,
int  y 
)

set start location

Definition at line 1130 of file environment_nav2D.cpp.

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1040 of file environment_nav2D.cpp.

bool EnvironmentNAV2D::UpdateCost ( int  x,
int  y,
unsigned char  newcost 
)

update the traversability of a cell<x,y>

Definition at line 1157 of file environment_nav2D.cpp.


Member Data Documentation

Definition at line 266 of file environment_nav2D.h.

Definition at line 265 of file environment_nav2D.h.


The documentation for this class was generated from the following files:
 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:53