3D (x,y,theta) planning using lattice-based graph problem. For general structure see comments on parent class DiscreteSpaceInformation For info on lattice-based planning used here, you can check out the paper: Maxim Likhachev and Dave Ferguson, " Planning Long Dynamically-Feasible Maneuvers for Autonomous Vehicles", IJRR'09 More...
#include <environment_navxythetalat.h>
Public Member Functions | |
virtual void | EnsureHeuristicsUpdated (bool bGoalHeuristics) |
see comments on the same function in the parent class | |
EnvironmentNAVXYTHETALATTICE () | |
const EnvNAVXYTHETALATConfig_t * | GetEnvNavConfig () |
get internal configuration data structure | |
virtual int | GetEnvParameter (const char *parameter) |
returns the value of specific parameter - see function body for the list of parameters | |
void | GetEnvParms (int *size_x, int *size_y, double *startx, double *starty, double *starttheta, double *goalx, double *goaly, double *goaltheta, double *cellsize_m, double *nominalvel_mpersecs, double *timetoturn45degsinplace_secs, unsigned char *obsthresh, vector< SBPL_xytheta_mprimitive > *motionprimitiveV) |
returns environment parameters. Useful for creating a copy environment | |
virtual int | GetFromToHeuristic (int FromStateID, int ToStateID)=0 |
see comments on the same function in the parent class | |
virtual int | GetGoalHeuristic (int stateID)=0 |
see comments on the same function in the parent class | |
unsigned char | GetMapCost (int x, int y) |
returns the cost corresponding to the cell <x,y> | |
virtual void | GetPreds (int TargetStateID, vector< int > *PredIDV, vector< int > *CostV)=0 |
see comments on the same function in the parent class | |
virtual void | GetPredsofChangedEdges (vector< nav2dcell_t > const *changedcellsV, vector< int > *preds_of_changededgesIDV)=0 |
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)=0 |
see comments on the same function in the parent class | |
virtual void | GetSuccs (int SourceStateID, vector< int > *SuccIDV, vector< int > *CostV) |
see comments on the same function in the parent class | |
virtual void | GetSuccsofChangedEdges (vector< nav2dcell_t > const *changedcellsV, vector< int > *succs_of_changededgesIDV)=0 |
same as GetPredsofChangedEdges, but returns successor states. Both functions need to be present for incremental search | |
bool | InitializeEnv (const char *sEnvFile, const vector< sbpl_2Dpt_t > &perimeterptsV, const char *sMotPrimFile) |
initialization of environment from file. See .cfg files for examples it also takes the perimeter of the robot with respect to some reference point centered at x=0,y=0 and orientation = 0 (along x axis). The perimeter is defined in meters as a sequence of vertices of a polygon defining the perimeter. If vector is of zero size, then robot is assumed to be point robot (you may want to inflate all obstacles by its actual radius) Motion primitives file defines the motion primitives available to the robot | |
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, double startx, double starty, double starttheta, double goalx, double goaly, double goaltheta, double goaltol_x, double goaltol_y, double goaltol_theta, const vector< sbpl_2Dpt_t > &perimeterptsV, double cellsize_m, double nominalvel_mpersecs, double timetoturn45degsinplace_secs, unsigned char obsthresh, const char *sMotPrimFile) |
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) f A[x][y] >= obsthresh, then in the above equation it is assumed to be infinite. The cost also incorporates the length of a motion primitive and its cost_multiplier (see getcost function) 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, starttheta, goalx,goaly, goaltheta in meters/radians. 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 goaltolerances are currently ignored for explanation of perimeter, see comments for InitializeEnv function that reads all from file cellsize is discretization in meters nominalvel_mpersecs is assumed velocity of vehicle while moving forward in m/sec timetoturn45degsinplace_secs is rotational velocity in secs/45 degrees turn | |
bool | InitializeMDPCfg (MDPConfig *MDPCfg) |
see comments on the same function in the parent class | |
bool | IsObstacle (int x, int y) |
bool | IsValidConfiguration (int X, int Y, int Theta) |
returns false if robot intersects obstacles or lies outside of the map. Note this is pretty expensive operation since it computes the footprint of the robot based on its x,y,theta | |
bool | IsWithinMapCell (int X, int Y) |
returns true if cell is within map | |
bool | PoseContToDisc (double px, double py, double pth, int &ix, int &iy, int &ith) const |
Transform a pose into discretized form. The angle 'pth' is considered to be valid if it lies between -2pi and 2pi (some people will prefer 0<=pth<2pi, others -pi<pth<=pi, so this compromise should suit everyone). | |
bool | PoseDiscToCont (int ix, int iy, int ith, double &px, double &py, double &pth) const |
Transform grid indices into a continuous pose. The computed angle lies within 0<=pth<2pi. | |
void | PrintEnv_Config (FILE *fOut) |
see comments on the same function in the parent class | |
void | PrintTimeStat (FILE *fOut) |
prints time statistics | |
virtual void | PrintVars () |
prints environment variables for debugging | |
virtual void | SetAllActionsandAllOutcomes (CMDPSTATE *state)=0 |
see comments on the same function in the parent class | |
virtual void | SetAllPreds (CMDPSTATE *state) |
see comments on the same function in the parent class | |
virtual 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 | |
bool | SetMap (const unsigned char *mapdata) |
re-setting the whole 2D map transform from linear array mapdata to the 2D matrix used internally: Grid2D[x][y] = mapdata[x+y*width] | |
bool | UpdateCost (int x, int y, unsigned char newcost) |
update the traversability of a cell<x,y> | |
virtual | ~EnvironmentNAVXYTHETALATTICE () |
Protected Member Functions | |
void | CalculateFootprintForPose (EnvNAVXYTHETALAT3Dpt_t pose, vector< sbpl_2Dcell_t > *footprint) |
void | CalculateFootprintForPose (EnvNAVXYTHETALAT3Dpt_t pose, vector< sbpl_2Dcell_t > *footprint, const vector< sbpl_2Dpt_t > &FootprintPolygon) |
bool | CheckQuant (FILE *fOut) |
void | ComputeHeuristicValues () |
void | ComputeReplanningData () |
void | ComputeReplanningDataforAction (EnvNAVXYTHETALATAction_t *action) |
void | CreateStartandGoalStates () |
double | EuclideanDistance_m (int X1, int Y1, int X2, int Y2) |
virtual int | GetActionCost (int SourceX, int SourceY, int SourceTheta, EnvNAVXYTHETALATAction_t *action) |
virtual void | GetSuccs (int SourceStateID, vector< int > *SuccIDV, vector< int > *CostV, vector< EnvNAVXYTHETALATAction_t * > *actionindV=NULL)=0 |
bool | InitGeneral (vector< SBPL_xytheta_mprimitive > *motionprimitiveV) |
void | InitializeEnvConfig (vector< SBPL_xytheta_mprimitive > *motionprimitiveV) |
virtual void | InitializeEnvironment ()=0 |
virtual bool | IsValidCell (int X, int Y) |
void | PrecomputeActions () |
void | PrecomputeActionswithBaseMotionPrimitive (vector< SBPL_xytheta_mprimitive > *motionprimitiveV) |
void | PrecomputeActionswithCompleteMotionPrimitive (vector< SBPL_xytheta_mprimitive > *motionprimitiveV) |
void | PrintHeuristicValues () |
virtual void | ReadConfiguration (FILE *fCfg) |
bool | ReadinCell (EnvNAVXYTHETALAT3Dcell_t *cell, FILE *fIn) |
bool | ReadinMotionPrimitive (SBPL_xytheta_mprimitive *pMotPrim, FILE *fIn) |
bool | ReadinPose (EnvNAVXYTHETALAT3Dpt_t *pose, FILE *fIn) |
bool | ReadMotionPrimitives (FILE *fMotPrims) |
void | RemoveSourceFootprint (EnvNAVXYTHETALAT3Dpt_t sourcepose, vector< sbpl_2Dcell_t > *footprint) |
void | RemoveSourceFootprint (EnvNAVXYTHETALAT3Dpt_t sourcepose, vector< sbpl_2Dcell_t > *footprint, const vector< sbpl_2Dpt_t > &FootprintPolygon) |
void | SetConfiguration (int width, int height, const unsigned char *mapdata, int startx, int starty, int starttheta, int goalx, int goaly, int goaltheta, double cellsize_m, double nominalvel_mpersecs, double timetoturn45degsinplace_secs, const vector< sbpl_2Dpt_t > &robot_perimeterV) |
Protected Attributes | |
vector< EnvNAVXYTHETALAT3Dcell_t > | affectedpredstatesV |
vector< EnvNAVXYTHETALAT3Dcell_t > | affectedsuccstatesV |
bool | bNeedtoRecomputeGoalHeuristics |
bool | bNeedtoRecomputeStartHeuristics |
EnvironmentNAVXYTHETALAT_t | EnvNAVXYTHETALAT |
EnvNAVXYTHETALATConfig_t | EnvNAVXYTHETALATCfg |
SBPL2DGridSearch * | grid2Dsearchfromgoal |
SBPL2DGridSearch * | grid2Dsearchfromstart |
int | iteration |
3D (x,y,theta) planning using lattice-based graph problem. For general structure see comments on parent class DiscreteSpaceInformation For info on lattice-based planning used here, you can check out the paper: Maxim Likhachev and Dave Ferguson, " Planning Long Dynamically-Feasible Maneuvers for Autonomous Vehicles", IJRR'09
Definition at line 176 of file environment_navxythetalat.h.
Definition at line 47 of file environment_navxythetalat.cpp.
Definition at line 71 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::CalculateFootprintForPose | ( | EnvNAVXYTHETALAT3Dpt_t | pose, |
vector< sbpl_2Dcell_t > * | footprint | ||
) | [protected] |
Definition at line 1485 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::CalculateFootprintForPose | ( | EnvNAVXYTHETALAT3Dpt_t | pose, |
vector< sbpl_2Dcell_t > * | footprint, | ||
const vector< sbpl_2Dpt_t > & | FootprintPolygon | ||
) | [protected] |
Definition at line 1354 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::CheckQuant | ( | FILE * | fOut | ) | [protected] |
Definition at line 1578 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::ComputeHeuristicValues | ( | ) | [protected] |
Definition at line 1560 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::ComputeReplanningData | ( | ) | [protected] |
Definition at line 758 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::ComputeReplanningDataforAction | ( | EnvNAVXYTHETALATAction_t * | action | ) | [protected] |
Definition at line 655 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::CreateStartandGoalStates | ( | ) | [protected] |
void EnvironmentNAVXYTHETALATTICE::EnsureHeuristicsUpdated | ( | bool | bGoalHeuristics | ) | [virtual] |
see comments on the same function in the parent class
Reimplemented from DiscreteSpaceInformation.
Definition at line 1529 of file environment_navxythetalat.cpp.
double EnvironmentNAVXYTHETALATTICE::EuclideanDistance_m | ( | int | X1, |
int | Y1, | ||
int | X2, | ||
int | Y2 | ||
) | [protected] |
Definition at line 1345 of file environment_navxythetalat.cpp.
int EnvironmentNAVXYTHETALATTICE::GetActionCost | ( | int | SourceX, |
int | SourceY, | ||
int | SourceTheta, | ||
EnvNAVXYTHETALATAction_t * | action | ||
) | [protected, virtual] |
Reimplemented in EnvironmentNAVXYTHETAMLEVLAT.
Definition at line 1277 of file environment_navxythetalat.cpp.
get internal configuration data structure
Definition at line 1807 of file environment_navxythetalat.cpp.
int EnvironmentNAVXYTHETALATTICE::GetEnvParameter | ( | const char * | parameter | ) | [virtual] |
returns the value of specific parameter - see function body for the list of parameters
Definition at line 1983 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::GetEnvParms | ( | int * | size_x, |
int * | size_y, | ||
double * | startx, | ||
double * | starty, | ||
double * | starttheta, | ||
double * | goalx, | ||
double * | goaly, | ||
double * | goaltheta, | ||
double * | cellsize_m, | ||
double * | nominalvel_mpersecs, | ||
double * | timetoturn45degsinplace_secs, | ||
unsigned char * | obsthresh, | ||
vector< SBPL_xytheta_mprimitive > * | motionprimitiveV | ||
) |
returns environment parameters. Useful for creating a copy environment
Definition at line 1882 of file environment_navxythetalat.cpp.
virtual int EnvironmentNAVXYTHETALATTICE::GetFromToHeuristic | ( | int | FromStateID, |
int | ToStateID | ||
) | [pure virtual] |
see comments on the same function in the parent class
Implements DiscreteSpaceInformation.
Implemented in EnvironmentNAVXYTHETALAT.
virtual int EnvironmentNAVXYTHETALATTICE::GetGoalHeuristic | ( | int | stateID | ) | [pure virtual] |
see comments on the same function in the parent class
Implements DiscreteSpaceInformation.
Implemented in EnvironmentNAVXYTHETALAT.
unsigned char EnvironmentNAVXYTHETALATTICE::GetMapCost | ( | int | x, |
int | y | ||
) |
returns the cost corresponding to the cell <x,y>
Reimplemented in EnvironmentNAVXYTHETAMLEVLAT.
Definition at line 1929 of file environment_navxythetalat.cpp.
virtual void EnvironmentNAVXYTHETALATTICE::GetPreds | ( | int | TargetStateID, |
vector< int > * | PredIDV, | ||
vector< int > * | CostV | ||
) | [pure virtual] |
see comments on the same function in the parent class
Implemented in EnvironmentNAVXYTHETALAT.
virtual void EnvironmentNAVXYTHETALATTICE::GetPredsofChangedEdges | ( | vector< nav2dcell_t > const * | changedcellsV, |
vector< int > * | preds_of_changededgesIDV | ||
) | [pure 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
Implemented in EnvironmentNAVXYTHETALAT, and EnvironmentNAVXYTHETAMLEVLAT.
virtual int EnvironmentNAVXYTHETALATTICE::GetStartHeuristic | ( | int | stateID | ) | [pure virtual] |
see comments on the same function in the parent class
Implements DiscreteSpaceInformation.
Implemented in EnvironmentNAVXYTHETALAT.
void EnvironmentNAVXYTHETALATTICE::GetSuccs | ( | int | SourceStateID, |
vector< int > * | SuccIDV, | ||
vector< int > * | CostV | ||
) | [virtual] |
see comments on the same function in the parent class
Definition at line 1798 of file environment_navxythetalat.cpp.
virtual void EnvironmentNAVXYTHETALATTICE::GetSuccs | ( | int | SourceStateID, |
vector< int > * | SuccIDV, | ||
vector< int > * | CostV, | ||
vector< EnvNAVXYTHETALATAction_t * > * | actionindV = NULL |
||
) | [protected, pure virtual] |
Implemented in EnvironmentNAVXYTHETALAT.
virtual void EnvironmentNAVXYTHETALATTICE::GetSuccsofChangedEdges | ( | vector< nav2dcell_t > const * | changedcellsV, |
vector< int > * | succs_of_changededgesIDV | ||
) | [pure virtual] |
same as GetPredsofChangedEdges, but returns successor states. Both functions need to be present for incremental search
Implemented in EnvironmentNAVXYTHETALAT, and EnvironmentNAVXYTHETAMLEVLAT.
bool EnvironmentNAVXYTHETALATTICE::InitGeneral | ( | vector< SBPL_xytheta_mprimitive > * | motionprimitiveV | ) | [protected] |
Definition at line 1721 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::InitializeEnv | ( | const char * | sEnvFile, |
const vector< sbpl_2Dpt_t > & | perimeterptsV, | ||
const char * | sMotPrimFile | ||
) |
initialization of environment from file. See .cfg files for examples it also takes the perimeter of the robot with respect to some reference point centered at x=0,y=0 and orientation = 0 (along x axis). The perimeter is defined in meters as a sequence of vertices of a polygon defining the perimeter. If vector is of zero size, then robot is assumed to be point robot (you may want to inflate all obstacles by its actual radius) Motion primitives file defines the motion primitives available to the robot
Definition at line 1604 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::InitializeEnv | ( | const char * | sEnvFile | ) | [virtual] |
see comments on the same function in the parent class
Implements DiscreteSpaceInformation.
Definition at line 1642 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::InitializeEnv | ( | int | width, |
int | height, | ||
const unsigned char * | mapdata, | ||
double | startx, | ||
double | starty, | ||
double | starttheta, | ||
double | goalx, | ||
double | goaly, | ||
double | goaltheta, | ||
double | goaltol_x, | ||
double | goaltol_y, | ||
double | goaltol_theta, | ||
const vector< sbpl_2Dpt_t > & | perimeterptsV, | ||
double | cellsize_m, | ||
double | nominalvel_mpersecs, | ||
double | timetoturn45degsinplace_secs, | ||
unsigned char | obsthresh, | ||
const char * | sMotPrimFile | ||
) |
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) f A[x][y] >= obsthresh, then in the above equation it is assumed to be infinite. The cost also incorporates the length of a motion primitive and its cost_multiplier (see getcost function) 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, starttheta, goalx,goaly, goaltheta in meters/radians. 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 goaltolerances are currently ignored for explanation of perimeter, see comments for InitializeEnv function that reads all from file cellsize is discretization in meters nominalvel_mpersecs is assumed velocity of vehicle while moving forward in m/sec timetoturn45degsinplace_secs is rotational velocity in secs/45 degrees turn
mapdata | if mapdata is NULL the grid is initialized to all freespace |
Definition at line 1662 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::InitializeEnvConfig | ( | vector< SBPL_xytheta_mprimitive > * | motionprimitiveV | ) | [protected] |
Definition at line 1181 of file environment_navxythetalat.cpp.
virtual void EnvironmentNAVXYTHETALATTICE::InitializeEnvironment | ( | ) | [protected, pure virtual] |
Implemented in EnvironmentNAVXYTHETALAT.
bool EnvironmentNAVXYTHETALATTICE::InitializeMDPCfg | ( | MDPConfig * | MDPCfg | ) | [virtual] |
see comments on the same function in the parent class
Implements DiscreteSpaceInformation.
Definition at line 1736 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::IsObstacle | ( | int | x, |
int | y | ||
) |
returns true if cell is untraversable
Reimplemented in EnvironmentNAVXYTHETAMLEVLAT.
Definition at line 1870 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::IsValidCell | ( | int | X, |
int | Y | ||
) | [protected, virtual] |
Reimplemented in EnvironmentNAVXYTHETAMLEVLAT.
Definition at line 1233 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::IsValidConfiguration | ( | int | X, |
int | Y, | ||
int | Theta | ||
) |
returns false if robot intersects obstacles or lies outside of the map. Note this is pretty expensive operation since it computes the footprint of the robot based on its x,y,theta
Reimplemented in EnvironmentNAVXYTHETAMLEVLAT.
Definition at line 1246 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::IsWithinMapCell | ( | int | X, |
int | Y | ||
) |
returns true if cell is within map
Definition at line 1240 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::PoseContToDisc | ( | double | px, |
double | py, | ||
double | pth, | ||
int & | ix, | ||
int & | iy, | ||
int & | ith | ||
) | const |
Transform a pose into discretized form. The angle 'pth' is considered to be valid if it lies between -2pi and 2pi (some people will prefer 0<=pth<2pi, others -pi<pth<=pi, so this compromise should suit everyone).
Definition at line 1906 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::PoseDiscToCont | ( | int | ix, |
int | iy, | ||
int | ith, | ||
double & | px, | ||
double & | py, | ||
double & | pth | ||
) | const |
Transform grid indices into a continuous pose. The computed angle lies within 0<=pth<2pi.
Definition at line 1918 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::PrecomputeActions | ( | ) | [protected] |
Definition at line 1046 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::PrecomputeActionswithBaseMotionPrimitive | ( | vector< SBPL_xytheta_mprimitive > * | motionprimitiveV | ) | [protected] |
Definition at line 775 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::PrecomputeActionswithCompleteMotionPrimitive | ( | vector< SBPL_xytheta_mprimitive > * | motionprimitiveV | ) | [protected] |
Definition at line 899 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::PrintEnv_Config | ( | FILE * | fOut | ) | [virtual] |
see comments on the same function in the parent class
Implements DiscreteSpaceInformation.
Definition at line 1848 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::PrintHeuristicValues | ( | ) | [protected] |
Definition at line 1746 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::PrintTimeStat | ( | FILE * | fOut | ) |
prints time statistics
Definition at line 1858 of file environment_navxythetalat.cpp.
virtual void EnvironmentNAVXYTHETALATTICE::PrintVars | ( | ) | [inline, virtual] |
prints environment variables for debugging
Reimplemented in EnvironmentNAVXYTHETALAT.
Definition at line 360 of file environment_navxythetalat.h.
void EnvironmentNAVXYTHETALATTICE::ReadConfiguration | ( | FILE * | fCfg | ) | [protected, virtual] |
Definition at line 197 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::ReadinCell | ( | EnvNAVXYTHETALAT3Dcell_t * | cell, |
FILE * | fIn | ||
) | [protected] |
Definition at line 441 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::ReadinMotionPrimitive | ( | SBPL_xytheta_mprimitive * | pMotPrim, |
FILE * | fIn | ||
) | [protected] |
Definition at line 480 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::ReadinPose | ( | EnvNAVXYTHETALAT3Dpt_t * | pose, |
FILE * | fIn | ||
) | [protected] |
Definition at line 461 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::ReadMotionPrimitives | ( | FILE * | fMotPrims | ) | [protected] |
Definition at line 586 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::RemoveSourceFootprint | ( | EnvNAVXYTHETALAT3Dpt_t | sourcepose, |
vector< sbpl_2Dcell_t > * | footprint | ||
) | [protected] |
Definition at line 1518 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::RemoveSourceFootprint | ( | EnvNAVXYTHETALAT3Dpt_t | sourcepose, |
vector< sbpl_2Dcell_t > * | footprint, | ||
const vector< sbpl_2Dpt_t > & | FootprintPolygon | ||
) | [protected] |
Definition at line 1492 of file environment_navxythetalat.cpp.
virtual void EnvironmentNAVXYTHETALATTICE::SetAllActionsandAllOutcomes | ( | CMDPSTATE * | state | ) | [pure virtual] |
see comments on the same function in the parent class
Implements DiscreteSpaceInformation.
Implemented in EnvironmentNAVXYTHETALAT.
void EnvironmentNAVXYTHETALATTICE::SetAllPreds | ( | CMDPSTATE * | state | ) | [virtual] |
see comments on the same function in the parent class
Implements DiscreteSpaceInformation.
Definition at line 1789 of file environment_navxythetalat.cpp.
void EnvironmentNAVXYTHETALATTICE::SetConfiguration | ( | int | width, |
int | height, | ||
const unsigned char * | mapdata, | ||
int | startx, | ||
int | starty, | ||
int | starttheta, | ||
int | goalx, | ||
int | goaly, | ||
int | goaltheta, | ||
double | cellsize_m, | ||
double | nominalvel_mpersecs, | ||
double | timetoturn45degsinplace_secs, | ||
const vector< sbpl_2Dpt_t > & | robot_perimeterV | ||
) | [protected] |
mapdata | if mapdata is NULL the grid is initialized to all freespace |
Definition at line 126 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::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 1936 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::SetMap | ( | const unsigned char * | mapdata | ) |
re-setting the whole 2D map transform from linear array mapdata to the 2D matrix used internally: Grid2D[x][y] = mapdata[x+y*width]
Definition at line 1829 of file environment_navxythetalat.cpp.
bool EnvironmentNAVXYTHETALATTICE::UpdateCost | ( | int | x, |
int | y, | ||
unsigned char | newcost | ||
) |
update the traversability of a cell<x,y>
Definition at line 1813 of file environment_navxythetalat.cpp.
Definition at line 371 of file environment_navxythetalat.h.
Definition at line 370 of file environment_navxythetalat.h.
bool EnvironmentNAVXYTHETALATTICE::bNeedtoRecomputeGoalHeuristics [protected] |
Definition at line 376 of file environment_navxythetalat.h.
bool EnvironmentNAVXYTHETALATTICE::bNeedtoRecomputeStartHeuristics [protected] |
Definition at line 375 of file environment_navxythetalat.h.
Definition at line 369 of file environment_navxythetalat.h.
Definition at line 368 of file environment_navxythetalat.h.
Definition at line 378 of file environment_navxythetalat.h.
Definition at line 377 of file environment_navxythetalat.h.
int EnvironmentNAVXYTHETALATTICE::iteration [protected] |
Definition at line 372 of file environment_navxythetalat.h.