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

this class is NOT fully yet implemented, please do not use it! More...

#include <environment_nav2Duu.h>

Inheritance diagram for EnvironmentNAV2DUU:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 EnvironmentNAV2DUU ()
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
void GetPreds (int stateID, const vector< sbpl_BinaryHiddenVar_t > *updatedhvaluesV, vector< CMDPACTION > *IncomingDetActionV, vector< CMDPACTION > *IncomingStochActionV, vector< sbpl_BinaryHiddenVar_t > *StochActionNonpreferredOutcomeV)
 not fully implemented yet
void GetPreds (int TargetStateID, vector< int > *PredIDV, vector< int > *CostV)
 not fully implemented yet
int GetStartHeuristic (int stateID)
 see comments on the same function in the parent class
void GetSuccs (int SourceStateID, vector< int > *SuccIDV, vector< int > *CostV)
 not fully implemented yet
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, const float *uncertaintymapdata, 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 uncertaintymapdata is set up in the same way as mapdata in terms of the order in terms of the values, uncertaintymapdata specifies probabilities of being obstructed
bool InitializeMDPCfg (MDPConfig *MDPCfg)
 see comments on the same function in the parent class
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 SetAllActionsandAllOutcomes (CMDPSTATE *state)
 not fully implemented yet
void SetAllPreds (CMDPSTATE *state)
 not fully implemented yet
int SetGoal (int x, int y)
 set goal location
int SetStart (int x, int y)
 set start location
int SizeofCreatedEnv ()
 not fully implemented yet
int SizeofH ()
 not fully implemented yet
bool UpdateCost (int x, int y, unsigned char newcost)
 update the traversability of a cell<x,y>
 ~EnvironmentNAV2DUU ()

Private Member Functions

void Computedxy ()
void ComputeHeuristicValues ()
bool InitGeneral ()
void InitializeEnvConfig ()
void InitializeEnvironment ()
bool IsValidRobotPosition (int X, int Y)
bool IsWithinMapCell (int X, int Y)
void ReadConfiguration (FILE *fCfg)
void SetConfiguration (int width, int height, const unsigned char *mapdata, const float *uncertaintymapdata)

Private Attributes

EnvironmentNAV2DUU_t EnvNAV2DUU
EnvNAV2DUUConfig_t EnvNAV2DUUCfg

Detailed Description

this class is NOT fully yet implemented, please do not use it!

Definition at line 96 of file environment_nav2Duu.h.


Constructor & Destructor Documentation

Definition at line 45 of file environment_nav2Duu.cpp.

Definition at line 151 of file environment_nav2Duu.h.


Member Function Documentation

void EnvironmentNAV2DUU::Computedxy ( ) [private]

Definition at line 331 of file environment_nav2Duu.cpp.

Definition at line 394 of file environment_nav2Duu.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 509 of file environment_nav2Duu.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 526 of file environment_nav2Duu.cpp.

void EnvironmentNAV2DUU::GetPreds ( int  stateID,
const vector< sbpl_BinaryHiddenVar_t > *  updatedhvaluesV,
vector< CMDPACTION > *  IncomingDetActionV,
vector< CMDPACTION > *  IncomingStochActionV,
vector< sbpl_BinaryHiddenVar_t > *  StochActionNonpreferredOutcomeV 
)

not fully implemented yet

Definition at line 559 of file environment_nav2Duu.cpp.

void EnvironmentNAV2DUU::GetPreds ( int  TargetStateID,
vector< int > *  PredIDV,
vector< int > *  CostV 
) [inline]

not fully implemented yet

Definition at line 179 of file environment_nav2Duu.h.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 541 of file environment_nav2Duu.cpp.

void EnvironmentNAV2DUU::GetSuccs ( int  SourceStateID,
vector< int > *  SuccIDV,
vector< int > *  CostV 
) [inline]

not fully implemented yet

Definition at line 173 of file environment_nav2Duu.h.

bool EnvironmentNAV2DUU::InitGeneral ( ) [private]

Definition at line 482 of file environment_nav2Duu.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 447 of file environment_nav2Duu.cpp.

bool EnvironmentNAV2DUU::InitializeEnv ( int  width,
int  height,
const unsigned char *  mapdata,
const float *  uncertaintymapdata,
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 uncertaintymapdata is set up in the same way as mapdata in terms of the order in terms of the values, uncertaintymapdata specifies probabilities of being obstructed

Definition at line 465 of file environment_nav2Duu.cpp.

Definition at line 275 of file environment_nav2Duu.cpp.

Definition at line 263 of file environment_nav2Duu.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 498 of file environment_nav2Duu.cpp.

bool EnvironmentNAV2DUU::IsValidRobotPosition ( int  X,
int  Y 
) [private]

Definition at line 318 of file environment_nav2Duu.cpp.

bool EnvironmentNAV2DUU::IsWithinMapCell ( int  X,
int  Y 
) [private]

Definition at line 325 of file environment_nav2Duu.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 433 of file environment_nav2Duu.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 408 of file environment_nav2Duu.cpp.

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

Definition at line 57 of file environment_nav2Duu.cpp.

void EnvironmentNAV2DUU::SetAllActionsandAllOutcomes ( CMDPSTATE state) [inline, virtual]

not fully implemented yet

Implements DiscreteSpaceInformation.

Definition at line 161 of file environment_nav2Duu.h.

void EnvironmentNAV2DUU::SetAllPreds ( CMDPSTATE state) [inline, virtual]

not fully implemented yet

Implements DiscreteSpaceInformation.

Definition at line 167 of file environment_nav2Duu.h.

void EnvironmentNAV2DUU::SetConfiguration ( int  width,
int  height,
const unsigned char *  mapdata,
const float *  uncertaintymapdata 
) [private]

Definition at line 211 of file environment_nav2Duu.cpp.

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

set goal location

Definition at line 721 of file environment_nav2Duu.cpp.

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

set start location

Definition at line 747 of file environment_nav2Duu.cpp.

not fully implemented yet

Implements DiscreteSpaceInformation.

Definition at line 307 of file environment_nav2Duu.cpp.

not fully implemented yet

Definition at line 312 of file environment_nav2Duu.cpp.

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

update the traversability of a cell<x,y>

Definition at line 769 of file environment_nav2Duu.cpp.


Member Data Documentation

Definition at line 197 of file environment_nav2Duu.h.

Definition at line 196 of file environment_nav2Duu.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