35 #ifndef DLUX_GLOBAL_PLANNER_POTENTIAL_CALCULATOR_H 36 #define DLUX_GLOBAL_PLANNER_POTENTIAL_CALCULATOR_H 41 #include <geometry_msgs/Pose2D.h> 80 const geometry_msgs::Pose2D& start,
const geometry_msgs::Pose2D& goal) = 0;
86 #endif // DLUX_GLOBAL_PLANNER_POTENTIAL_CALCULATOR_H
virtual void initialize(ros::NodeHandle &private_nh, nav_core2::Costmap::Ptr costmap, CostInterpreter::Ptr cost_interpreter)
Initialize function.
virtual unsigned int updatePotentials(PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal)=0
Main potential calculation function.
virtual ~PotentialCalculator()=default
std::shared_ptr< CostInterpreter > Ptr
Plugin interface for calculating a numerical score (potential) for some subset of the cells in the co...
std::shared_ptr< Costmap > Ptr
CostInterpreter::Ptr cost_interpreter_