The CostmapPlannerExecution binds a global costmap to the AbstractPlannerExecution and uses the nav_core/BaseCostmapPlanner class as base plugin interface. This class makes move_base_flex compatible to the old move_base. More...
#include <costmap_planner_execution.h>

Public Types | |
| typedef boost::shared_ptr < costmap_2d::Costmap2DROS > | CostmapPtr |
Public Member Functions | |
| 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 | ~CostmapPlannerExecution () |
| Destructor. | |
Private Member Functions | |
| 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, if a goal tolerance is enabled in the planner plugin. | |
| mbf_abstract_nav::MoveBaseFlexConfig | toAbstract (const MoveBaseFlexConfig &config) |
Private Attributes | |
| 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) | |
| std::string | planner_name_ |
| Name of the planner assigned by the class loader. | |
The CostmapPlannerExecution binds a global costmap to the AbstractPlannerExecution and uses the nav_core/BaseCostmapPlanner class as base plugin interface. This class makes move_base_flex compatible to the old move_base.
Definition at line 57 of file costmap_planner_execution.h.
| typedef boost::shared_ptr<costmap_2d::Costmap2DROS> mbf_costmap_nav::CostmapPlannerExecution::CostmapPtr |
Definition at line 60 of file costmap_planner_execution.h.
| mbf_costmap_nav::CostmapPlannerExecution::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.
| condition | Thread sleep condition variable, to wake up connected threads |
| costmap | Shared pointer to the costmap. |
Definition at line 47 of file costmap_planner_execution.cpp.
Destructor.
Definition at line 61 of file costmap_planner_execution.cpp.
| uint32_t mbf_costmap_nav::CostmapPlannerExecution::makePlan | ( | const geometry_msgs::PoseStamped & | start, |
| const geometry_msgs::PoseStamped & | goal, | ||
| double | tolerance, | ||
| std::vector< geometry_msgs::PoseStamped > & | plan, | ||
| double & | cost, | ||
| std::string & | message | ||
| ) | [private, virtual] |
Calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance, if a goal tolerance is enabled in the planner plugin.
| start | The start pose for planning |
| goal | The goal pose for planning |
| tolerance | The goal tolerance |
| plan | The computed plan by the plugin |
| cost | The computed costs for the corresponding plan |
| message | An optional message which should correspond with the returned outcome |
Reimplemented from mbf_abstract_nav::AbstractPlannerExecution.
Definition at line 75 of file costmap_planner_execution.cpp.
| mbf_abstract_nav::MoveBaseFlexConfig mbf_costmap_nav::CostmapPlannerExecution::toAbstract | ( | const MoveBaseFlexConfig & | config | ) | [private] |
Definition at line 65 of file costmap_planner_execution.cpp.
Shared pointer to the global planner costmap.
Definition at line 104 of file costmap_planner_execution.h.
bool mbf_costmap_nav::CostmapPlannerExecution::lock_costmap_ [private] |
Whether to lock costmap before calling the planner (see issue #4 for details)
Definition at line 107 of file costmap_planner_execution.h.
std::string mbf_costmap_nav::CostmapPlannerExecution::planner_name_ [private] |
Name of the planner assigned by the class loader.
Definition at line 110 of file costmap_planner_execution.h.