35 #ifndef DLUX_PLUGINS_GRADIENT_PATH_H 36 #define DLUX_PLUGINS_GRADIENT_PATH_H 53 const geometry_msgs::Pose2D& start,
const geometry_msgs::Pose2D& goal,
54 double& path_cost)
override;
68 #endif // DLUX_PLUGINS_GRADIENT_PATH_H
nav_grid::Index gridStep(const dlux_global_planner::PotentialGrid &potential_grid, const nav_grid::Index &index)
nav_grid::VectorNavGrid< double > grady_
void calculateGradient(const dlux_global_planner::PotentialGrid &potential_grid, const nav_grid::Index &index)
bool grid_step_near_high_
nav_2d_msgs::Path2D getPath(const dlux_global_planner::PotentialGrid &potential_grid, const geometry_msgs::Pose2D &start, const geometry_msgs::Pose2D &goal, double &path_cost) override
std::shared_ptr< CostInterpreter > Ptr
Traceback function that creates a smooth gradient from the start to the goal.
bool shouldGridStep(const dlux_global_planner::PotentialGrid &potential_grid, const nav_grid::Index &index)
nav_grid::VectorNavGrid< double > gradx_
void initialize(ros::NodeHandle &private_nh, dlux_global_planner::CostInterpreter::Ptr cost_interpreter) override