48 const std::string &planner_name,
51 const MoveBaseFlexConfig &config)
52 : AbstractPlannerExecution(planner_name, planner_ptr, toAbstract(config)),
53 costmap_ptr_(costmap_ptr)
66 mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
67 abstract_config.planner_frequency = config.planner_frequency;
68 abstract_config.planner_patience = config.planner_patience;
69 abstract_config.planner_max_retries = config.planner_max_retries;
70 return abstract_config;
74 const geometry_msgs::PoseStamped &goal,
76 std::vector<geometry_msgs::PoseStamped> &plan,
82 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(
costmap_ptr_->getCostmap()->getMutex()));
83 return planner_->makePlan(start, goal, tolerance, plan, cost, message);
85 return planner_->makePlan(start, goal, tolerance, plan, cost, message);
const CostmapWrapper::Ptr & costmap_ptr_
Shared pointer to the global planner costmap.
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 param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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.
mbf_abstract_core::AbstractPlanner::Ptr planner_
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)