41 #ifndef MBF_COSTMAP_NAV__COSTMAP_PLANNER_EXECUTION_H_    42 #define MBF_COSTMAP_NAV__COSTMAP_PLANNER_EXECUTION_H_    47 #include "mbf_costmap_nav/MoveBaseFlexConfig.h"    72       const std::string &planner_name,
    75       const MoveBaseFlexConfig &config);
   102   mbf_abstract_nav::MoveBaseFlexConfig 
toAbstract(
const MoveBaseFlexConfig &config);
   116       const geometry_msgs::PoseStamped &
start,
   117       const geometry_msgs::PoseStamped &
goal,
   119       std::vector<geometry_msgs::PoseStamped> &plan,
   121       std::string &message);
 const CostmapWrapper::Ptr & costmap_ptr_
Shared pointer to the global planner costmap. 
std::string planner_name_
Name of the planner assigned by the class loader. 
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)
Calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance...
virtual ~CostmapPlannerExecution()
Destructor. 
bool lock_costmap_
Whether to lock costmap before calling the planner (see issue #4 for details) 
CostmapPlannerExecution(const std::string &planner_name, const mbf_costmap_core::CostmapPlanner::Ptr &planner_ptr, const CostmapWrapper::Ptr &costmap_ptr, const MoveBaseFlexConfig &config)
Constructor. 
void preRun()
Implementation-specific setup function, called right before execution. This method overrides abstract...
The CostmapPlannerExecution binds a global costmap to the AbstractPlannerExecution and uses the nav_c...
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)
void postRun()
Implementation-specific cleanup function, called right after execution. This method overrides abstrac...