Public Member Functions | Protected Attributes | List of all members
dlux_global_planner::PotentialCalculator Class Referenceabstract

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_
 

Detailed Description

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.

Constructor & Destructor Documentation

dlux_global_planner::PotentialCalculator::PotentialCalculator ( )
inline

Definition at line 55 of file potential_calculator.h.

virtual dlux_global_planner::PotentialCalculator::~PotentialCalculator ( )
virtualdefault

Member Function Documentation

virtual void dlux_global_planner::PotentialCalculator::initialize ( ros::NodeHandle private_nh,
nav_core2::Costmap::Ptr  costmap,
CostInterpreter::Ptr  cost_interpreter 
)
inlinevirtual

Initialize function.

Can be overridden to grab parameters or direct access to the costmap

Parameters
private_nhNodeHandle to read parameters from
costmapPointer to costmap (possibly for tracking changes)
cost_interpreterCostInterpreter pointer

Definition at line 67 of file potential_calculator.h.

virtual unsigned int dlux_global_planner::PotentialCalculator::updatePotentials ( PotentialGrid potential_grid,
const geometry_msgs::Pose2D &  start,
const geometry_msgs::Pose2D &  goal 
)
pure virtual

Main potential calculation function.

Parameters
potential_gridpotentials are written into here
startStart pose, in the same frame as the potential
goalGoal pose, in the same frame as the potential
Returns
Number of cells expanded. Used for comparing expansion strategies.

Member Data Documentation

CostInterpreter::Ptr dlux_global_planner::PotentialCalculator::cost_interpreter_
protected

Definition at line 82 of file potential_calculator.h.


The documentation for this class was generated from the following file:


dlux_global_planner
Author(s):
autogenerated on Sun Jan 10 2021 04:08:52