37 #ifndef NAV_CORE_BASE_GLOBAL_PLANNER_H 38 #define NAV_CORE_BASE_GLOBAL_PLANNER_H 40 #include <geometry_msgs/PoseStamped.h> 57 virtual bool makePlan(
const geometry_msgs::PoseStamped& start,
58 const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan) = 0;
68 virtual bool makePlan(
const geometry_msgs::PoseStamped& start,
69 const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan,
93 #endif // NAV_CORE_BASE_GLOBAL_PLANNER_H
virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)=0
Initialization function for the BaseGlobalPlanner.
virtual ~BaseGlobalPlanner()
Virtual destructor for the interface.
virtual bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)=0
Given a goal pose in the world, compute a plan.
Provides an interface for global planners used in navigation. All global planners written as plugins ...
virtual bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost)
Given a goal pose in the world, compute a plan.