$search

EnvironmentROBARM Class Reference

planar kinematic robot arm of variable number of degrees of freedom More...

#include <environment_robarm.h>

Inheritance diagram for EnvironmentROBARM:
Inheritance graph
[legend]

List of all members.

Public Member Functions

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 TargetStateID, vector< int > *PredIDV, vector< int > *CostV)
 see comments on the same function in the parent class
int GetStartHeuristic (int stateID)
 see comments on the same function in the parent class
void GetSuccs (int SourceStateID, vector< int > *SuccIDV, vector< int > *CostV)
 see comments on the same function in the parent class
bool InitializeEnv (const char *sEnvFile)
 initialize environment from a file (see .cfg files in robotarm directory for example)
bool InitializeMDPCfg (MDPConfig *MDPCfg)
 initialize MDP config with IDs of start/goal
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)
 prints out some runtime 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
int SizeofCreatedEnv ()
 see comments on the same function in the parent class
 ~EnvironmentROBARM ()

Private Member Functions

bool AreEquivalent (int State1ID, int State2ID)
 returns true if two states meet the same condition, brief this is used in some planners to figure out if two states are the same in some lower-dimensional manifold for example, in robotarm planning, two states could be equivalent if their end effectors are at the same position unless overwritten in a child class, this function is not implemented
void Cell2ContXY (int x, int y, double *pX, double *pY)
void ComputeContAngles (short unsigned int coord[NUMOFLINKS], double angle[NUMOFLINKS])
void ComputeCoord (double angle[NUMOFLINKS], short unsigned int coord[NUMOFLINKS])
int ComputeEndEffectorPos (double angles[NUMOFLINKS], short unsigned int *pX, short unsigned int *pY)
void ComputeHeuristicValues ()
void ContXY2Cell (double x, double y, short unsigned int *pX, short unsigned int *pY)
int cost (short unsigned int state1coord[], short unsigned int state2coord[])
void Create2DStateSpace (State2D ***statespace2D)
EnvROBARMHashEntry_tCreateNewHashEntry (short unsigned int *coord, int numofcoord, short unsigned int endeffx, short unsigned int endeffy)
void CreateStartandGoalStates ()
void Delete2DStateSpace (State2D ***statespace2D)
void DiscretizeAngles ()
int distanceincoord (unsigned short *statecoord1, unsigned short *statecoord2)
int GetEdgeCost (int FromStateID, int ToStateID)
unsigned int GETHASHBIN (short unsigned int *coord, int numofcoord)
EnvROBARMHashEntry_tGetHashEntry (short unsigned int *coord, int numofcoord, bool bIsGoal)
unsigned int GetHeurBasedonCoord (short unsigned int coord[NUMOFLINKS])
int GetRandomState ()
void GetRandomSuccsatDistance (int SourceStateID, std::vector< int > *SuccIDV, std::vector< int > *CLowV)
 the following two functions generate succs/preds at some domain-dependent distance. The number of generated succs/preds is up to the environment. NOTE: they MUST generate goal state as a succ/pred if it is within the distance from the state CLowV is the corresponding vector of lower bounds on the costs from the state to the successor states (or vice versa for preds function) unless overwritten in a child class, this function is not implemented
void InitializeEnvConfig ()
bool InitializeEnvironment ()
void InitializeState2D (State2D *state, short unsigned int x, short unsigned int y)
bool IsValidCell (int X, int Y)
int IsValidCoord (short unsigned int coord[NUMOFLINKS], char **Grid2D=NULL, vector< CELLV > *pTestedCells=NULL)
int IsValidLineSegment (double x0, double y0, double x1, double y1, char **Grid2D, vector< CELLV > *pTestedCells)
bool IsWithinMapCell (int X, int Y)
void printangles (FILE *fOut, short unsigned int *coord, bool bGoal, bool bVerbose, bool bLocal)
void PrintHashTableHist ()
void PrintHeader (FILE *fOut)
void PrintSuccGoal (int SourceStateID, int costtogoal, bool bVerbose, bool bLocal, FILE *fOut)
void ReadConfiguration (FILE *fCfg)
void ReInitializeState2D (State2D *state)
void Search2DwithQueue (State2D **statespace, int *HeurGrid, int searchstartx, int searchstarty)

Private Attributes

EnvironmentROBARM_t EnvROBARM
EnvROBARMConfig_t EnvROBARMCfg

Detailed Description

planar kinematic robot arm of variable number of degrees of freedom

Definition at line 119 of file environment_robarm.h.


Constructor & Destructor Documentation

EnvironmentROBARM::~EnvironmentROBARM (  )  [inline]

Definition at line 165 of file environment_robarm.h.


Member Function Documentation

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

returns true if two states meet the same condition, brief this is used in some planners to figure out if two states are the same in some lower-dimensional manifold for example, in robotarm planning, two states could be equivalent if their end effectors are at the same position unless overwritten in a child class, this function is not implemented

Reimplemented from DiscreteSpaceInformation.

Definition at line 1753 of file environment_robarm.cpp.

void EnvironmentROBARM::Cell2ContXY ( int  x,
int  y,
double *  pX,
double *  pY 
) [private]

Definition at line 876 of file environment_robarm.cpp.

void EnvironmentROBARM::ComputeContAngles ( short unsigned int  coord[NUMOFLINKS],
double  angle[NUMOFLINKS] 
) [private]

Definition at line 833 of file environment_robarm.cpp.

void EnvironmentROBARM::ComputeCoord ( double  angle[NUMOFLINKS],
short unsigned int  coord[NUMOFLINKS] 
) [private]

Definition at line 843 of file environment_robarm.cpp.

int EnvironmentROBARM::ComputeEndEffectorPos ( double  angles[NUMOFLINKS],
short unsigned int *  pX,
short unsigned int *  pY 
) [private]

Definition at line 895 of file environment_robarm.cpp.

void EnvironmentROBARM::ComputeHeuristicValues (  )  [private]

Definition at line 413 of file environment_robarm.cpp.

void EnvironmentROBARM::ContXY2Cell ( double  x,
double  y,
short unsigned int *  pX,
short unsigned int *  pY 
) [private]

Definition at line 882 of file environment_robarm.cpp.

int EnvironmentROBARM::cost ( short unsigned int  state1coord[],
short unsigned int  state2coord[] 
) [private]

Definition at line 1040 of file environment_robarm.cpp.

void EnvironmentROBARM::Create2DStateSpace ( State2D ***  statespace2D  )  [private]

Definition at line 384 of file environment_robarm.cpp.

EnvROBARMHashEntry_t * EnvironmentROBARM::CreateNewHashEntry ( short unsigned int *  coord,
int  numofcoord,
short unsigned int  endeffx,
short unsigned int  endeffy 
) [private]

Definition at line 160 of file environment_robarm.cpp.

void EnvironmentROBARM::CreateStartandGoalStates (  )  [private]
void EnvironmentROBARM::Delete2DStateSpace ( State2D ***  statespace2D  )  [private]

Definition at line 400 of file environment_robarm.cpp.

void EnvironmentROBARM::DiscretizeAngles (  )  [private]

Definition at line 818 of file environment_robarm.cpp.

int EnvironmentROBARM::distanceincoord ( unsigned short *  statecoord1,
unsigned short *  statecoord2 
) [private]

Definition at line 212 of file environment_robarm.cpp.

int EnvironmentROBARM::GetEdgeCost ( int  FromStateID,
int  ToStateID 
) [private]

Definition at line 1628 of file environment_robarm.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1169 of file environment_robarm.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1212 of file environment_robarm.cpp.

unsigned int EnvironmentROBARM::GETHASHBIN ( short unsigned int *  coord,
int  numofcoord 
) [private]

Definition at line 72 of file environment_robarm.cpp.

EnvROBARMHashEntry_t * EnvironmentROBARM::GetHashEntry ( short unsigned int *  coord,
int  numofcoord,
bool  bIsGoal 
) [private]

Definition at line 114 of file environment_robarm.cpp.

unsigned int EnvironmentROBARM::GetHeurBasedonCoord ( short unsigned int  coord[NUMOFLINKS]  )  [private]

Definition at line 857 of file environment_robarm.cpp.

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

see comments on the same function in the parent class

Definition at line 1480 of file environment_robarm.cpp.

int EnvironmentROBARM::GetRandomState (  )  [private]

Definition at line 1649 of file environment_robarm.cpp.

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

the following two functions generate succs/preds at some domain-dependent distance. The number of generated succs/preds is up to the environment. NOTE: they MUST generate goal state as a succ/pred if it is within the distance from the state CLowV is the corresponding vector of lower bounds on the costs from the state to the successor states (or vice versa for preds function) unless overwritten in a child class, this function is not implemented

Reimplemented from DiscreteSpaceInformation.

Definition at line 1489 of file environment_robarm.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1230 of file environment_robarm.cpp.

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

see comments on the same function in the parent class

Definition at line 1397 of file environment_robarm.cpp.

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

initialize environment from a file (see .cfg files in robotarm directory for example)

Implements DiscreteSpaceInformation.

Definition at line 1132 of file environment_robarm.cpp.

void EnvironmentROBARM::InitializeEnvConfig (  )  [private]

Definition at line 1068 of file environment_robarm.cpp.

bool EnvironmentROBARM::InitializeEnvironment (  )  [private]

Definition at line 1074 of file environment_robarm.cpp.

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

initialize MDP config with IDs of start/goal

Implements DiscreteSpaceInformation.

Definition at line 1159 of file environment_robarm.cpp.

void EnvironmentROBARM::InitializeState2D ( State2D state,
short unsigned int  x,
short unsigned int  y 
) [private]

Definition at line 234 of file environment_robarm.cpp.

bool EnvironmentROBARM::IsValidCell ( int  X,
int  Y 
) [private]
int EnvironmentROBARM::IsValidCoord ( short unsigned int  coord[NUMOFLINKS],
char **  Grid2D = NULL,
vector< CELLV > *  pTestedCells = NULL 
) [private]

Definition at line 971 of file environment_robarm.cpp.

int EnvironmentROBARM::IsValidLineSegment ( double  x0,
double  y0,
double  x1,
double  y1,
char **  Grid2D,
vector< CELLV > *  pTestedCells 
) [private]

Definition at line 924 of file environment_robarm.cpp.

bool EnvironmentROBARM::IsWithinMapCell ( int  X,
int  Y 
) [private]
void EnvironmentROBARM::printangles ( FILE *  fOut,
short unsigned int *  coord,
bool  bGoal,
bool  bVerbose,
bool  bLocal 
) [private]

Definition at line 468 of file environment_robarm.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1369 of file environment_robarm.cpp.

void EnvironmentROBARM::PrintHashTableHist (  )  [private]

Definition at line 88 of file environment_robarm.cpp.

void EnvironmentROBARM::PrintHeader ( FILE *  fOut  )  [private]

Definition at line 1379 of file environment_robarm.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1271 of file environment_robarm.cpp.

void EnvironmentROBARM::PrintSuccGoal ( int  SourceStateID,
int  costtogoal,
bool  bVerbose,
bool  bLocal,
FILE *  fOut 
) [private]

Definition at line 1309 of file environment_robarm.cpp.

void EnvironmentROBARM::PrintTimeStat ( FILE *  fOut  ) 

prints out some runtime statistics

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

Definition at line 655 of file environment_robarm.cpp.

void EnvironmentROBARM::ReInitializeState2D ( State2D state  )  [private]

Definition at line 228 of file environment_robarm.cpp.

void EnvironmentROBARM::Search2DwithQueue ( State2D **  statespace,
int *  HeurGrid,
int  searchstartx,
int  searchstarty 
) [private]

Definition at line 309 of file environment_robarm.cpp.

void EnvironmentROBARM::SetAllActionsandAllOutcomes ( CMDPSTATE state  )  [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1388 of file environment_robarm.cpp.

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

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1256 of file environment_robarm.cpp.

int EnvironmentROBARM::SizeofCreatedEnv (  )  [virtual]

see comments on the same function in the parent class

Implements DiscreteSpaceInformation.

Definition at line 1265 of file environment_robarm.cpp.


Member Data Documentation

Definition at line 174 of file environment_robarm.h.

Definition at line 173 of file environment_robarm.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


sbpl
Author(s): Maxim Likhachev/maximl@seas.upenn.edu
autogenerated on Fri Mar 1 14:18:59 2013