Determining the heuristic value by calculating a 2D path from each grid cell of the map to the goal and using the path length as expected distance. More...
#include <PathCostHeuristic.h>
Public Member Functions | |
bool | calculateDistances (const PlanningState &from, const PlanningState &to) |
Calculates for each grid cell of the map a 2D path to the cell (to.x, to.y). For forward planning 'to' is supposed to be the goal state, for backward planning 'to' is supposed to be the start state. More... | |
virtual double | getHValue (const PlanningState ¤t, const PlanningState &to) const |
PathCostHeuristic (double cell_size, int num_angle_bins, double step_cost, double diff_angle_cost, double max_step_width, double inflation_radius) | |
void | updateMap (gridmap_2d::GridMap2DPtr map) |
virtual | ~PathCostHeuristic () |
Public Member Functions inherited from footstep_planner::Heuristic | |
HeuristicType | getHeuristicType () const |
Heuristic (double cell_size, int num_angle_bins, HeuristicType type) | |
virtual | ~Heuristic () |
Private Member Functions | |
void | resetGrid () |
Private Attributes | |
double | ivDiffAngleCost |
int | ivGoalX |
int | ivGoalY |
boost::shared_ptr< SBPL2DGridSearch > | ivGridSearchPtr |
double | ivInflationRadius |
gridmap_2d::GridMap2DPtr | ivMapPtr |
double | ivMaxStepWidth |
unsigned char ** | ivpGrid |
double | ivStepCost |
Static Private Attributes | |
static const int | cvObstacleThreshold = 200 |
Additional Inherited Members | |
Public Types inherited from footstep_planner::Heuristic | |
enum | HeuristicType { EUCLIDEAN =0, EUCLIDEAN_STEPCOST =1, PATH_COST =2 } |
Protected Attributes inherited from footstep_planner::Heuristic | |
double | ivCellSize |
const HeuristicType | ivHeuristicType |
int | ivNumAngleBins |
Determining the heuristic value by calculating a 2D path from each grid cell of the map to the goal and using the path length as expected distance.
The heuristic value consists of the following factors:
Definition at line 45 of file PathCostHeuristic.h.
footstep_planner::PathCostHeuristic::PathCostHeuristic | ( | double | cell_size, |
int | num_angle_bins, | ||
double | step_cost, | ||
double | diff_angle_cost, | ||
double | max_step_width, | ||
double | inflation_radius | ||
) |
Definition at line 26 of file PathCostHeuristic.cpp.
|
virtual |
Definition at line 43 of file PathCostHeuristic.cpp.
bool footstep_planner::PathCostHeuristic::calculateDistances | ( | const PlanningState & | from, |
const PlanningState & | to | ||
) |
Calculates for each grid cell of the map a 2D path to the cell (to.x, to.y). For forward planning 'to' is supposed to be the goal state, for backward planning 'to' is supposed to be the start state.
Definition at line 104 of file PathCostHeuristic.cpp.
|
virtual |
Implements footstep_planner::Heuristic.
Definition at line 51 of file PathCostHeuristic.cpp.
|
private |
Definition at line 174 of file PathCostHeuristic.cpp.
void footstep_planner::PathCostHeuristic::updateMap | ( | gridmap_2d::GridMap2DPtr | map | ) |
Definition at line 135 of file PathCostHeuristic.cpp.
|
staticprivate |
Definition at line 71 of file PathCostHeuristic.h.
|
private |
Definition at line 76 of file PathCostHeuristic.h.
|
private |
Definition at line 80 of file PathCostHeuristic.h.
|
private |
Definition at line 81 of file PathCostHeuristic.h.
|
private |
Definition at line 84 of file PathCostHeuristic.h.
|
private |
Definition at line 78 of file PathCostHeuristic.h.
|
private |
Definition at line 83 of file PathCostHeuristic.h.
|
private |
Definition at line 77 of file PathCostHeuristic.h.
|
private |
Definition at line 73 of file PathCostHeuristic.h.
|
private |
Definition at line 75 of file PathCostHeuristic.h.