39 #ifndef MBF_ABSTRACT_CORE__ABSTRACT_PLANNER_H_    40 #define MBF_ABSTRACT_CORE__ABSTRACT_PLANNER_H_    45 #include <boost/shared_ptr.hpp>    46 #include <geometry_msgs/PoseStamped.h>    86       virtual uint32_t 
makePlan(
const geometry_msgs::PoseStamped &start, 
const geometry_msgs::PoseStamped &goal,
    87                                 double tolerance, std::vector<geometry_msgs::PoseStamped> &plan, 
double &cost,
    88                                 std::string &message) = 0;
 virtual bool cancel()=0
Requests the planner to cancel, e.g. if it takes too much time. 
AbstractPlanner()
Constructor. 
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. 
boost::shared_ptr< ::mbf_abstract_core::AbstractPlanner > Ptr
virtual ~AbstractPlanner()
Destructor.