EnvIntervalLat Class Reference

#include <envInterval.h>

Inheritance diagram for EnvIntervalLat:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void ConvertStateIDPathintoXYThetaPath (vector< int > *stateIDPath, vector< SBPL_4Dpt_t > *xythetaPath)
 Converts a path of state IDs (returned from the planner) into a paths of points (x,y,theta,time).
void dumpDynamicObstaclesToFile ()
void dumpEnvironmentToFile ()
void dumpStatesToFile ()
void GetCoordFromState (int stateID, int &x, int &y, int &theta, int &t, bool &opt) const
 Gets the coordinate (and whether it is optimal) given a state ID.
void GetCoordFromState (int stateID, int &x, int &y, int &theta, int &t) const
 Gets the coordinate given a state ID.
void getExpansions (vector< SBPL_4Dpt_t > *p)
virtual int GetFromToHeuristic (int FromStateID, int ToStateID)
virtual int GetGoalHeuristic (int stateID)
virtual int GetStartHeuristic (int stateID)
int GetStateFromCoord (int x, int y, int theta, int t)
 Returns the state ID given the coordinate.
virtual void GetSuccs (int SourceStateID, vector< int > *SuccIDV, vector< int > *CostV, vector< bool > *OptV, bool optSearch, vector< envIntervalLatAction_t * > *actionV=NULL)
 A function that gets the successors of a state. Used by the planner.
void PrintState (int stateID, bool bVerbose, FILE *fOut=NULL)
virtual void PrintVars ()
void Relax (int stateID)
 A function that updates the time value for a state. Should only be called by the planner.
bool setDynamicObstacles (vector< SBPL_DynamicObstacle_t > dynObs, bool reset_states=true)
 Sets the dynamic obstacles.
int SetGoal (double x, double y, double theta)
 Sets the goal state of the environment. You still have to set the goal state of the planner after this.
int SetStart (double x, double y, double theta, double startTime)
 Sets the start state of the environment. You still have to set the start state of the planner after this.
virtual int SizeofCreatedEnv ()
 ~EnvIntervalLat ()

Protected Member Functions

void ClearStates ()
envIntervalLatHashEntry_tCreateNewHashEntry (int X, int Y, int Theta, int interval, int T, bool Opt)
envIntervalLatHashEntry_tgetEntryFromID (int id)
unsigned int GETHASHBIN (unsigned int X, unsigned int Y, unsigned int Theta, unsigned int interval, bool Opt)
envIntervalLatHashEntry_tGetHashEntry (int X, int Y, int Theta, int interval, int T, bool Opt)
virtual void GetPreds (int TargetStateID, vector< int > *PredIDV, vector< int > *CostV)
void GetPredsofChangedEdges (vector< nav2dcell_t > const *changedcellsV, vector< int > *preds_of_changededgesIDV)
void GetSuccsofChangedEdges (vector< nav2dcell_t > const *changedcellsV, vector< int > *succs_of_changededgesIDV)
virtual void InitializeEnvironment ()
void PrintHashTableHist ()
virtual void SetAllActionsandAllOutcomes (CMDPSTATE *state)

Protected Attributes

vector
< envIntervalLatHashEntry_t * > * 
Coord2StateIDHashTable
int HashTableSize
vector
< envIntervalLatHashEntry_t * > 
StateID2CoordTable

Detailed Description

Definition at line 447 of file envInterval.h.


Constructor & Destructor Documentation

EnvIntervalLat::~EnvIntervalLat (  ) 

Definition at line 92 of file envInterval.cpp.


Member Function Documentation

void EnvIntervalLat::ClearStates (  )  [protected]

Definition at line 3120 of file envInterval.cpp.

void EnvIntervalLat::ConvertStateIDPathintoXYThetaPath ( vector< int > *  stateIDPath,
vector< SBPL_4Dpt_t > *  xythetaPath 
) [virtual]

Converts a path of state IDs (returned from the planner) into a paths of points (x,y,theta,time).

Parameters:
stateIDPath The path of state IDs
xythetaPath The path of points

Implements DiscreteSpaceTimeIntervalInformation.

Definition at line 2854 of file envInterval.cpp.

envIntervalLatHashEntry_t * EnvIntervalLat::CreateNewHashEntry ( int  X,
int  Y,
int  Theta,
int  interval,
int  T,
bool  Opt 
) [protected]

Definition at line 3228 of file envInterval.cpp.

void EnvIntervalLat::dumpDynamicObstaclesToFile (  ) 

Definition at line 3764 of file envInterval.cpp.

void EnvIntervalLat::dumpEnvironmentToFile (  ) 

Definition at line 3740 of file envInterval.cpp.

void EnvIntervalLat::dumpStatesToFile (  ) 

Definition at line 3730 of file envInterval.cpp.

void EnvIntervalLat::GetCoordFromState ( int  stateID,
int &  x,
int &  y,
int &  theta,
int &  t,
bool &  opt 
) const

Gets the coordinate (and whether it is optimal) given a state ID.

Definition at line 2827 of file envInterval.cpp.

void EnvIntervalLat::GetCoordFromState ( int  stateID,
int &  x,
int &  y,
int &  theta,
int &  t 
) const [virtual]

Gets the coordinate given a state ID.

Implements DiscreteSpaceTimeIntervalInformation.

Definition at line 2820 of file envInterval.cpp.

envIntervalLatHashEntry_t * EnvIntervalLat::getEntryFromID ( int  id  )  [protected, virtual]

Implements EnvIntervalLattice.

Definition at line 3140 of file envInterval.cpp.

void EnvIntervalLat::getExpansions ( vector< SBPL_4Dpt_t > *  p  )  [virtual]

Reimplemented from DiscreteSpaceTimeIntervalInformation.

Definition at line 3716 of file envInterval.cpp.

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

Implements EnvIntervalLattice.

Definition at line 3784 of file envInterval.cpp.

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

Implements EnvIntervalLattice.

Definition at line 3813 of file envInterval.cpp.

unsigned int EnvIntervalLat::GETHASHBIN ( unsigned int  X,
unsigned int  Y,
unsigned int  Theta,
unsigned int  interval,
bool  Opt 
) [protected]

Definition at line 3685 of file envInterval.cpp.

envIntervalLatHashEntry_t * EnvIntervalLat::GetHashEntry ( int  X,
int  Y,
int  Theta,
int  interval,
int  T,
bool  Opt 
) [protected]

Definition at line 3174 of file envInterval.cpp.

void EnvIntervalLat::GetPreds ( int  TargetStateID,
vector< int > *  PredIDV,
vector< int > *  CostV 
) [protected, virtual]

Implements EnvIntervalLattice.

Definition at line 3434 of file envInterval.cpp.

void EnvIntervalLat::GetPredsofChangedEdges ( vector< nav2dcell_t > const *  changedcellsV,
vector< int > *  preds_of_changededgesIDV 
) [protected, virtual]

Implements EnvIntervalLattice.

Definition at line 3581 of file envInterval.cpp.

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

Implements EnvIntervalLattice.

Definition at line 3857 of file envInterval.cpp.

int EnvIntervalLat::GetStateFromCoord ( int  x,
int  y,
int  theta,
int  t 
)

Returns the state ID given the coordinate.

Definition at line 2836 of file envInterval.cpp.

void EnvIntervalLat::GetSuccs ( int  SourceStateID,
vector< int > *  SuccIDV,
vector< int > *  CostV,
vector< bool > *  OptV,
bool  optSearch,
vector< envIntervalLatAction_t * > *  actionV = NULL 
) [virtual]

A function that gets the successors of a state. Used by the planner.

Implements EnvIntervalLattice.

Definition at line 3288 of file envInterval.cpp.

void EnvIntervalLat::GetSuccsofChangedEdges ( vector< nav2dcell_t > const *  changedcellsV,
vector< int > *  succs_of_changededgesIDV 
) [protected, virtual]

Implements EnvIntervalLattice.

Definition at line 3616 of file envInterval.cpp.

void EnvIntervalLat::InitializeEnvironment (  )  [protected, virtual]

Implements EnvIntervalLattice.

Definition at line 3653 of file envInterval.cpp.

void EnvIntervalLat::PrintHashTableHist (  )  [protected]

Definition at line 3691 of file envInterval.cpp.

void EnvIntervalLat::PrintState ( int  stateID,
bool  bVerbose,
FILE *  fOut = NULL 
)

Definition at line 3144 of file envInterval.cpp.

virtual void EnvIntervalLat::PrintVars (  )  [inline, virtual]

Reimplemented from EnvIntervalLattice.

Definition at line 521 of file envInterval.h.

void EnvIntervalLat::Relax ( int  stateID  )  [virtual]

A function that updates the time value for a state. Should only be called by the planner.

Reimplemented from DiscreteSpaceTimeIntervalInformation.

Definition at line 3427 of file envInterval.cpp.

void EnvIntervalLat::SetAllActionsandAllOutcomes ( CMDPSTATE *  state  )  [protected, virtual]

Implements EnvIntervalLattice.

Definition at line 3504 of file envInterval.cpp.

bool EnvIntervalLat::setDynamicObstacles ( vector< SBPL_DynamicObstacle_t dynObs,
bool  reset_states = true 
) [virtual]

Sets the dynamic obstacles.

Parameters:
dynObs The dynamic obstacle vector
reset_states This resets the states between replans. This should always be true. This will reset even the start and goal states so make sure that SetStart and SetGoal are called after this.
Returns:
True on success

Implements DiscreteSpaceTimeIntervalInformation.

Definition at line 3085 of file envInterval.cpp.

int EnvIntervalLat::SetGoal ( double  x,
double  y,
double  theta 
) [virtual]

Sets the goal state of the environment. You still have to set the goal state of the planner after this.

Parameters:
x The goal x coordinate (meters)
y The goal y coordinate (meters)
theta The goal theta (radians)
Returns:
The state ID of the goal state

Implements DiscreteSpaceTimeIntervalInformation.

Definition at line 2978 of file envInterval.cpp.

int EnvIntervalLat::SetStart ( double  x,
double  y,
double  theta,
double  startTime 
) [virtual]

Sets the start state of the environment. You still have to set the start state of the planner after this.

Parameters:
x The start x coordinate (meters)
y The start y coordinate (meters)
theta The start theta (radians)
startTime The start time (seconds)
Returns:
The state ID of the start state

Implements DiscreteSpaceTimeIntervalInformation.

Definition at line 3035 of file envInterval.cpp.

int EnvIntervalLat::SizeofCreatedEnv (  )  [virtual]

Definition at line 3904 of file envInterval.cpp.


Member Data Documentation

Definition at line 534 of file envInterval.h.

Definition at line 533 of file envInterval.h.

Definition at line 536 of file envInterval.h.


The documentation for this class was generated from the following files:
 All Classes Files Functions Variables Typedefs Defines


sbpl_dynamic_planner
Author(s): Michael Phillips, Maxim Likhachev
autogenerated on Fri Jan 11 09:41:06 2013