Plugin interface for calculating a numerical score (potential) for some subset of the cells in the costmap. More...
#include <potential_calculator.h>
Public Member Functions | |
virtual void | initialize (ros::NodeHandle &private_nh, nav_core2::Costmap::Ptr costmap, CostInterpreter::Ptr cost_interpreter) |
Initialize function. More... | |
PotentialCalculator () | |
virtual unsigned int | updatePotentials (PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal)=0 |
Main potential calculation function. More... | |
virtual | ~PotentialCalculator ()=default |
Protected Attributes | |
CostInterpreter::Ptr | cost_interpreter_ |
Plugin interface for calculating a numerical score (potential) for some subset of the cells in the costmap.
The potential should be zero at the goal and grow higher from there. See README for more details
Definition at line 52 of file potential_calculator.h.
|
inline |
Definition at line 55 of file potential_calculator.h.
|
virtualdefault |
|
inlinevirtual |
Initialize function.
Can be overridden to grab parameters or direct access to the costmap
private_nh | NodeHandle to read parameters from |
costmap | Pointer to costmap (possibly for tracking changes) |
cost_interpreter | CostInterpreter pointer |
Definition at line 67 of file potential_calculator.h.
|
pure virtual |
Main potential calculation function.
potential_grid | potentials are written into here |
start | Start pose, in the same frame as the potential |
goal | Goal pose, in the same frame as the potential |
|
protected |
Definition at line 82 of file potential_calculator.h.