#include <environment_cart_planner.h>
Public Member Functions | |
bool | ConvertStateIDPathintoXYThetaPath (vector< int > *stateIDPath, vector< EnvNAVXYTHETACARTLAT3Dpt_t > *xythetaPath) |
converts a path given by stateIDs into a sequence of coordinates. Note that since motion primitives are short actions represented as a sequence of points, the path returned by this function contains much more points than the number of points in the input path. The returned coordinates are in meters,meters,radians | |
EnvironmentNAVXYTHETACARTLAT () | |
void | GetCoordFromState (int stateID, int &x, int &y, int &theta, int &cartangle) const |
returns state coordinates of state with ID=stateID | |
virtual int | GetFromToHeuristic (int FromStateID, int ToStateID) |
see comments on the same function in the parent class | |
virtual int | GetGoalHeuristic (int stateID) |
see comments on the same function in the parent class | |
virtual void | GetPreds (int TargetStateID, vector< int > *PredIDV, vector< int > *CostV) |
returns all predecessors states and corresponding costs of actions | |
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 int | GetStartHeuristic (int stateID) |
see comments on the same function in the parent class | |
int | GetStateFromCoord (int x, int y, int theta, int cartangle) |
returns stateID for a state with coords x,y,theta | |
virtual void | GetSuccs (int SourceStateID, vector< int > *SuccIDV, vector< int > *CostV, vector< EnvNAVXYTHETACARTLATAction_t * > *actionindV=NULL) |
returns all successors states, costs of corresponding actions and pointers to corresponding actions, each of which is a motion primitive if actionindV is NULL, then pointers to actions are not returned | |
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 | |
void | PrintState (int stateID, bool bVerbose, FILE *fOut=NULL) |
prints state info (coordinates) into file | |
virtual void | PrintVars () |
see comments on the same function in the parent class | |
virtual void | SetAllActionsandAllOutcomes (CMDPSTATE *state) |
see comments on the same function in the parent class | |
int | SetGoal (double x, double y, double theta, double cartangle) |
sets goal in meters/radians | |
void | SetGoalTolerance (double tol_x, double tol_y, double tol_theta, double tol_cartangle) |
sets goal tolerance. (Note goal tolerance is ignored currently) | |
int | SetStart (double x, double y, double theta, double cartangle) |
sets start in meters/radians | |
virtual int | SizeofCreatedEnv () |
see comments on the same function in the parent class | |
~EnvironmentNAVXYTHETACARTLAT () | |
Protected Member Functions | |
EnvNAVXYTHETACARTLATHashEntry_t * | CreateNewHashEntry_hash (int X, int Y, int Theta, int CartAngle) |
EnvNAVXYTHETACARTLATHashEntry_t * | CreateNewHashEntry_lookup (int X, int Y, int Theta, int CartAngle) |
unsigned int | GETHASHBIN (unsigned int X, unsigned int Y, unsigned int Theta, unsigned int CartAngle) |
EnvNAVXYTHETACARTLATHashEntry_t * | GetHashEntry_hash (int X, int Y, int Theta, int CartAngle) |
EnvNAVXYTHETACARTLATHashEntry_t * | GetHashEntry_lookup (int X, int Y, int Theta, int CartAngle) |
virtual void | InitializeEnvironment () |
void | PrintHashTableHist (FILE *fOut) |
Protected Attributes | |
vector < EnvNAVXYTHETACARTLATHashEntry_t * > * | Coord2StateIDHashTable |
EnvNAVXYTHETACARTLATHashEntry_t ** | Coord2StateIDHashTable_lookup |
EnvNAVXYTHETACARTLATHashEntry_t *(EnvironmentNAVXYTHETACARTLAT::* | CreateNewHashEntry )(int X, int Y, int Theta, int CartAngle) |
EnvNAVXYTHETACARTLATHashEntry_t *(EnvironmentNAVXYTHETACARTLAT::* | GetHashEntry )(int X, int Y, int Theta, int CartAngle) |
int | HashTableSize |
vector < EnvNAVXYTHETACARTLATHashEntry_t * > | StateID2CoordTable |
Definition at line 423 of file environment_cart_planner.h.
EnvironmentNAVXYTHETACARTLAT::EnvironmentNAVXYTHETACARTLAT | ( | ) | [inline] |
Definition at line 427 of file environment_cart_planner.h.
EnvironmentNAVXYTHETACARTLAT::~EnvironmentNAVXYTHETACARTLAT | ( | ) |
Definition at line 2418 of file environment_cart_planner.cpp.
bool EnvironmentNAVXYTHETACARTLAT::ConvertStateIDPathintoXYThetaPath | ( | vector< int > * | stateIDPath, | |
vector< EnvNAVXYTHETACARTLAT3Dpt_t > * | xythetaPath | |||
) |
converts a path given by stateIDs into a sequence of coordinates. Note that since motion primitives are short actions represented as a sequence of points, the path returned by this function contains much more points than the number of points in the input path. The returned coordinates are in meters,meters,radians
Definition at line 2463 of file environment_cart_planner.cpp.
EnvNAVXYTHETACARTLATHashEntry_t * EnvironmentNAVXYTHETACARTLAT::CreateNewHashEntry_hash | ( | int | X, | |
int | Y, | |||
int | Theta, | |||
int | CartAngle | |||
) | [protected] |
Definition at line 2790 of file environment_cart_planner.cpp.
EnvNAVXYTHETACARTLATHashEntry_t * EnvironmentNAVXYTHETACARTLAT::CreateNewHashEntry_lookup | ( | int | X, | |
int | Y, | |||
int | Theta, | |||
int | CartAngle | |||
) | [protected] |
Definition at line 2733 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::GetCoordFromState | ( | int | stateID, | |
int & | x, | |||
int & | y, | |||
int & | theta, | |||
int & | cartangle | |||
) | const |
returns state coordinates of state with ID=stateID
Definition at line 2445 of file environment_cart_planner.cpp.
int EnvironmentNAVXYTHETACARTLAT::GetFromToHeuristic | ( | int | FromStateID, | |
int | ToStateID | |||
) | [virtual] |
see comments on the same function in the parent class
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 3194 of file environment_cart_planner.cpp.
int EnvironmentNAVXYTHETACARTLAT::GetGoalHeuristic | ( | int | stateID | ) | [virtual] |
see comments on the same function in the parent class
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 3223 of file environment_cart_planner.cpp.
unsigned int EnvironmentNAVXYTHETACARTLAT::GETHASHBIN | ( | unsigned int | X, | |
unsigned int | Y, | |||
unsigned int | Theta, | |||
unsigned int | CartAngle | |||
) | [protected] |
Definition at line 3164 of file environment_cart_planner.cpp.
EnvNAVXYTHETACARTLATHashEntry_t * EnvironmentNAVXYTHETACARTLAT::GetHashEntry_hash | ( | int | X, | |
int | Y, | |||
int | Theta, | |||
int | CartAngle | |||
) | [protected] |
Definition at line 2693 of file environment_cart_planner.cpp.
EnvNAVXYTHETACARTLATHashEntry_t * EnvironmentNAVXYTHETACARTLAT::GetHashEntry_lookup | ( | int | X, | |
int | Y, | |||
int | Theta, | |||
int | CartAngle | |||
) | [protected] |
Definition at line 2686 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::GetPreds | ( | int | TargetStateID, | |
vector< int > * | PredIDV, | |||
vector< int > * | CostV | |||
) | [virtual] |
returns all predecessors states and corresponding costs of actions
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 2906 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::GetPredsofChangedEdges | ( | vector< nav2dcell_t > const * | changedcellsV, | |
vector< int > * | preds_of_changededgesIDV | |||
) | [virtual] |
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
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 3033 of file environment_cart_planner.cpp.
int EnvironmentNAVXYTHETACARTLAT::GetStartHeuristic | ( | int | stateID | ) | [virtual] |
see comments on the same function in the parent class
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 3247 of file environment_cart_planner.cpp.
int EnvironmentNAVXYTHETACARTLAT::GetStateFromCoord | ( | int | x, | |
int | y, | |||
int | theta, | |||
int | cartangle | |||
) |
returns stateID for a state with coords x,y,theta
Definition at line 2453 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::GetSuccs | ( | int | SourceStateID, | |
vector< int > * | SuccIDV, | |||
vector< int > * | CostV, | |||
vector< EnvNAVXYTHETACARTLATAction_t * > * | actionindV = NULL | |||
) | [virtual] |
returns all successors states, costs of corresponding actions and pointers to corresponding actions, each of which is a motion primitive if actionindV is NULL, then pointers to actions are not returned
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 2842 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::GetSuccsofChangedEdges | ( | vector< nav2dcell_t > const * | changedcellsV, | |
vector< int > * | succs_of_changededgesIDV | |||
) | [virtual] |
same as GetPredsofChangedEdges, but returns successor states. Both functions need to be present for incremental search
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 3066 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::InitializeEnvironment | ( | ) | [protected, virtual] |
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 3103 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::PrintHashTableHist | ( | FILE * | fOut | ) | [protected] |
Definition at line 3169 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::PrintState | ( | int | stateID, | |
bool | bVerbose, | |||
FILE * | fOut = NULL | |||
) |
prints state info (coordinates) into file
Definition at line 2658 of file environment_cart_planner.cpp.
virtual void EnvironmentNAVXYTHETACARTLAT::PrintVars | ( | ) | [inline, virtual] |
see comments on the same function in the parent class
Reimplemented from EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 495 of file environment_cart_planner.h.
void EnvironmentNAVXYTHETACARTLAT::SetAllActionsandAllOutcomes | ( | CMDPSTATE * | state | ) | [virtual] |
see comments on the same function in the parent class
Implements EnvironmentNAVXYTHETACARTLATTICE.
Definition at line 2965 of file environment_cart_planner.cpp.
int EnvironmentNAVXYTHETACARTLAT::SetGoal | ( | double | x, | |
double | y, | |||
double | theta, | |||
double | cartangle | |||
) |
sets goal in meters/radians
Definition at line 2565 of file environment_cart_planner.cpp.
void EnvironmentNAVXYTHETACARTLAT::SetGoalTolerance | ( | double | tol_x, | |
double | tol_y, | |||
double | tol_theta, | |||
double | tol_cartangle | |||
) | [inline] |
sets goal tolerance. (Note goal tolerance is ignored currently)
< not used yet
Definition at line 444 of file environment_cart_planner.h.
int EnvironmentNAVXYTHETACARTLAT::SetStart | ( | double | x, | |
double | y, | |||
double | theta, | |||
double | cartangle | |||
) |
sets start in meters/radians
Definition at line 2614 of file environment_cart_planner.cpp.
int EnvironmentNAVXYTHETACARTLAT::SizeofCreatedEnv | ( | ) | [virtual] |
see comments on the same function in the parent class
Definition at line 3273 of file environment_cart_planner.cpp.
vector<EnvNAVXYTHETACARTLATHashEntry_t*>* EnvironmentNAVXYTHETACARTLAT::Coord2StateIDHashTable [protected] |
Definition at line 501 of file environment_cart_planner.h.
EnvNAVXYTHETACARTLATHashEntry_t** EnvironmentNAVXYTHETACARTLAT::Coord2StateIDHashTable_lookup [protected] |
Definition at line 505 of file environment_cart_planner.h.
EnvNAVXYTHETACARTLATHashEntry_t*(EnvironmentNAVXYTHETACARTLAT::* EnvironmentNAVXYTHETACARTLAT::CreateNewHashEntry)(int X, int Y, int Theta, int CartAngle) [protected] |
Definition at line 516 of file environment_cart_planner.h.
EnvNAVXYTHETACARTLATHashEntry_t*(EnvironmentNAVXYTHETACARTLAT::* EnvironmentNAVXYTHETACARTLAT::GetHashEntry)(int X, int Y, int Theta, int CartAngle) [protected] |
Definition at line 515 of file environment_cart_planner.h.
int EnvironmentNAVXYTHETACARTLAT::HashTableSize [protected] |
Definition at line 495 of file environment_cart_planner.h.
vector<EnvNAVXYTHETACARTLATHashEntry_t*> EnvironmentNAVXYTHETACARTLAT::StateID2CoordTable [protected] |
Definition at line 503 of file environment_cart_planner.h.