Public Types | Public Member Functions | Protected Member Functions
mbf_costmap_core::CostmapPlanner Class Reference

Provides an interface for global planners used in navigation. All global planners written to work as MBF plugins must adhere to this interface. Alternatively, this class can also operate as a wrapper for old API nav_core-based plugins, providing backward compatibility. More...

#include <costmap_planner.h>

Inheritance diagram for mbf_costmap_core::CostmapPlanner:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< ::mbf_costmap_core::CostmapPlanner
Ptr

Public Member Functions

virtual bool cancel ()=0
 Requests the planner to cancel, e.g. if it takes too much time.
virtual void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)=0
 Initialization function for the CostmapPlanner.
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)=0
 Given a goal pose in the world, compute a plan.
virtual ~CostmapPlanner ()
 Virtual destructor for the interface.

Protected Member Functions

 CostmapPlanner ()

Detailed Description

Provides an interface for global planners used in navigation. All global planners written to work as MBF plugins must adhere to this interface. Alternatively, this class can also operate as a wrapper for old API nav_core-based plugins, providing backward compatibility.

Definition at line 52 of file costmap_planner.h.


Member Typedef Documentation

Reimplemented from mbf_abstract_core::AbstractPlanner.

Definition at line 55 of file costmap_planner.h.


Constructor & Destructor Documentation

Virtual destructor for the interface.

Definition at line 103 of file costmap_planner.h.

Definition at line 106 of file costmap_planner.h.


Member Function Documentation

virtual bool mbf_costmap_core::CostmapPlanner::cancel ( ) [pure virtual]

Requests the planner to cancel, e.g. if it takes too much time.

Remarks:
New on MBF API
Returns:
True if a cancel has been successfully requested, false if not implemented.

Implements mbf_abstract_core::AbstractPlanner.

virtual void mbf_costmap_core::CostmapPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
) [pure virtual]

Initialization function for the CostmapPlanner.

Parameters:
nameThe name of this planner
costmap_rosA pointer to the ROS wrapper of the costmap to use for planning
virtual uint32_t mbf_costmap_core::CostmapPlanner::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
double  tolerance,
std::vector< geometry_msgs::PoseStamped > &  plan,
double &  cost,
std::string &  message 
) [pure virtual]

Given a goal pose in the world, compute a plan.

Parameters:
startThe start pose
goalThe goal pose
toleranceIf the goal is obstructed, how many meters the planner can relax the constraint in x and y before failing
planThe plan... filled by the planner
costThe cost for the the plan
messageOptional more detailed outcome as a string
Returns:
Result code as described on GetPath action result: SUCCESS = 0 1..9 are reserved as plugin specific non-error results FAILURE = 50 # Unspecified failure, only used for old, non-mfb_core based plugins CANCELED = 51 INVALID_START = 52 INVALID_GOAL = 53 NO_PATH_FOUND = 54 PAT_EXCEEDED = 55 EMPTY_PATH = 56 TF_ERROR = 57 NOT_INITIALIZED = 58 INVALID_PLUGIN = 59 INTERNAL_ERROR = 60 71..99 are reserved as plugin specific errors

Implements mbf_abstract_core::AbstractPlanner.


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


mbf_costmap_core
Author(s): Jorge Santos , Sebastian Pütz
autogenerated on Mon Jun 17 2019 20:11:38