34 #ifndef NAV_CORE2_GLOBAL_PLANNER_H 35 #define NAV_CORE2_GLOBAL_PLANNER_H 39 #include <nav_2d_msgs/Path2D.h> 40 #include <nav_2d_msgs/Pose2DStamped.h> 78 virtual nav_2d_msgs::Path2D
makePlan(
const nav_2d_msgs::Pose2DStamped& start,
79 const nav_2d_msgs::Pose2DStamped& goal) = 0;
83 #endif // NAV_CORE2_GLOBAL_PLANNER_H
virtual void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, Costmap::Ptr costmap)=0
Initialization function for the GlobalPlanner.
Provides an interface for global planners used in navigation.
virtual ~GlobalPlanner()
Virtual Destructor.
virtual nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped &start, const nav_2d_msgs::Pose2DStamped &goal)=0
Run the global planner to make a plan starting at the start and ending at the goal.
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr