Public Types | Public Member Functions | Private Member Functions | Private Attributes
mbf_costmap_nav::CostmapPlannerExecution Class Reference

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>

Inheritance diagram for mbf_costmap_nav::CostmapPlannerExecution:
Inheritance graph
[legend]

List of all members.

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

CostmapPtrcostmap_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.

Detailed Description

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.


Member Typedef Documentation

Definition at line 60 of file costmap_planner_execution.h.


Constructor & Destructor Documentation

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.

Parameters:
conditionThread sleep condition variable, to wake up connected threads
costmapShared 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.


Member Function Documentation

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.

Parameters:
startThe start pose for planning
goalThe goal pose for planning
toleranceThe goal tolerance
planThe computed plan by the plugin
costThe computed costs for the corresponding plan
messageAn optional message which should correspond with the returned outcome
Returns:
An outcome number, see also the action definition in the GetPath.action file

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.


Member Data Documentation

Shared pointer to the global planner costmap.

Definition at line 104 of file costmap_planner_execution.h.

Whether to lock costmap before calling the planner (see issue #4 for details)

Definition at line 107 of file costmap_planner_execution.h.

Name of the planner assigned by the class loader.

Definition at line 110 of file costmap_planner_execution.h.


The documentation for this class was generated from the following files:


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Mon Jun 17 2019 20:11:40