35 #ifndef DLUX_GLOBAL_PLANNER_DLUX_GLOBAL_PLANNER_H 36 #define DLUX_GLOBAL_PLANNER_DLUX_GLOBAL_PLANNER_H 43 #include <nav_2d_msgs/Pose2DStamped.h> 63 nav_2d_msgs::Path2D
makePlan(
const nav_2d_msgs::Pose2DStamped& start,
64 const nav_2d_msgs::Pose2DStamped& goal)
override;
71 virtual bool isPlanValid(
const nav_2d_msgs::Path2D& path)
const;
90 unsigned int goal_x,
unsigned int goal_y);
104 virtual bool shouldReturnNewPath(
const nav_2d_msgs::Path2D& new_path,
const double new_path_cost)
const;
133 #endif // DLUX_GLOBAL_PLANNER_DLUX_GLOBAL_PLANNER_H boost::shared_ptr< Traceback > traceback_
virtual bool shouldReturnCachedPathImmediately() const
Whether the planner should always return a valid cached path without running the planning algorithm...
nav_core2::Costmap::Ptr costmap_
CostInterpreter::Ptr cost_interpreter_
PotentialGrid potential_grid_
boost::shared_ptr< PotentialCalculator > calculator_
pluginlib::ClassLoader< PotentialCalculator > calc_loader_
double improvement_threshold_
nav_2d_msgs::Path2D cached_path_
unsigned int cached_goal_y_
virtual bool hasValidCachedPath(const geometry_msgs::Pose2D &local_goal, unsigned int goal_x, unsigned int goal_y)
Check whether there is a valid cached path where the goal hasn't changed.
unsigned int cached_goal_x_
Plugin-based global wavefront planner that conforms to the nav_core2 GlobalPlanner interface...
nav_grid_pub_sub::ScaleGridPublisher< float > potential_pub_
pluginlib::ClassLoader< Traceback > traceback_loader_
std::shared_ptr< CostInterpreter > Ptr
virtual bool shouldReturnNewPath(const nav_2d_msgs::Path2D &new_path, const double new_path_cost) const
Given a cached path is available and a new path, should the new path be the one returned?
nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped &start, const nav_2d_msgs::Pose2DStamped &goal) override
virtual bool isPlanValid(const nav_2d_msgs::Path2D &path) const
Check the costmap for any obstacles on this path.
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr