39 #ifndef MBF_COSTMAP_CORE__COSTMAP_PLANNER_H_    40 #define MBF_COSTMAP_CORE__COSTMAP_PLANNER_H_    82       virtual uint32_t 
makePlan(
const geometry_msgs::PoseStamped &start, 
const geometry_msgs::PoseStamped &goal,
    83                                 double tolerance, std::vector<geometry_msgs::PoseStamped> &plan, 
double &cost,
    84                                 std::string &message) = 0;
 virtual uint32_t makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan, double &cost, std::string &message)=0
Given a goal pose in the world, compute a plan. 
virtual bool cancel()=0
Requests the planner to cancel, e.g. if it takes too much time. 
Provides an interface for global planners used in navigation. All global planners written to work as ...
virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)=0
Initialization function for the CostmapPlanner. 
virtual ~CostmapPlanner()
Virtual destructor for the interface. 
boost::shared_ptr< ::mbf_costmap_core::CostmapPlanner > Ptr