41 #include <mbf_msgs/GetPathResult.h> 50 const MoveBaseFlexConfig& config)
51 : AbstractPlannerExecution(planner_name, planner_ptr, tf_listener_ptr, toAbstract(config)), costmap_ptr_(costmap_ptr)
64 mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
65 abstract_config.planner_frequency = config.planner_frequency;
66 abstract_config.planner_patience = config.planner_patience;
67 abstract_config.planner_max_retries = config.planner_max_retries;
68 return abstract_config;
72 const geometry_msgs::PoseStamped &goal,
74 std::vector<geometry_msgs::PoseStamped> &plan,
83 const std::string frame =
costmap_ptr_->getGlobalFrameID();
84 geometry_msgs::PoseStamped g_start, g_goal;
87 return mbf_msgs::GetPathResult::TF_ERROR;
90 return mbf_msgs::GetPathResult::TF_ERROR;
94 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(
costmap_ptr_->getCostmap()->getMutex()));
95 return planner_->makePlan(g_start, g_goal, tolerance, plan, cost, message);
97 return planner_->makePlan(g_start, g_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
CostmapPlannerExecution(const std::string &planner_name, const mbf_costmap_core::CostmapPlanner::Ptr &planner_ptr, const TFPtr &tf_listener_ptr, const CostmapWrapper::Ptr &costmap_ptr, const MoveBaseFlexConfig &config)
Constructor.
bool lock_costmap_
Whether to lock costmap before calling the planner (see issue #4 for details)
mbf_abstract_core::AbstractPlanner::Ptr planner_
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)
const TFPtr tf_listener_ptr_
bool transformPose(const TF &tf, const std::string &target_frame, const ros::Duration &timeout, const geometry_msgs::PoseStamped &in, geometry_msgs::PoseStamped &out)