41 #ifndef MBF_COSTMAP_NAV__COSTMAP_PLANNER_EXECUTION_H_ 42 #define MBF_COSTMAP_NAV__COSTMAP_PLANNER_EXECUTION_H_ 45 #include <mbf_costmap_nav/MoveBaseFlexConfig.h> 68 const std::string name,
71 const MoveBaseFlexConfig &config,
72 boost::function<
void()> setup_fn,
73 boost::function<
void()> cleanup_fn);
82 mbf_abstract_nav::MoveBaseFlexConfig
toAbstract(
const MoveBaseFlexConfig &config);
96 const geometry_msgs::PoseStamped &
start,
97 const geometry_msgs::PoseStamped &goal,
99 std::vector<geometry_msgs::PoseStamped> &plan,
101 std::string &message);
std::string planner_name_
Name of the planner assigned by the class loader.
CostmapPlannerExecution(const std::string name, const mbf_costmap_core::CostmapPlanner::Ptr &planner_ptr, CostmapPtr &costmap, const MoveBaseFlexConfig &config, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
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)
Calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance...
virtual ~CostmapPlannerExecution()
Destructor.
CostmapPtr & costmap_ptr_
Shared pointer to the global planner costmap.
bool lock_costmap_
Whether to lock costmap before calling the planner (see issue #4 for details)
The CostmapPlannerExecution binds a global costmap to the AbstractPlannerExecution and uses the nav_c...
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)
boost::shared_ptr< costmap_2d::Costmap2DROS > CostmapPtr