Public Member Functions | Protected Member Functions | List of all members
nav_core::BaseGlobalPlanner Class Referenceabstract

Provides an interface for global planners used in navigation. All global planners written as plugins for the navigation stack must adhere to this interface. More...

#include <base_global_planner.h>

Public Member Functions

virtual void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)=0
 Initialization function for the BaseGlobalPlanner. More...
 
virtual bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)=0
 Given a goal pose in the world, compute a plan. More...
 
virtual bool makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost)
 Given a goal pose in the world, compute a plan. More...
 
virtual ~BaseGlobalPlanner ()
 Virtual destructor for the interface. More...
 

Protected Member Functions

 BaseGlobalPlanner ()
 

Detailed Description

Provides an interface for global planners used in navigation. All global planners written as plugins for the navigation stack must adhere to this interface.

Definition at line 48 of file base_global_planner.h.

Constructor & Destructor Documentation

virtual nav_core::BaseGlobalPlanner::~BaseGlobalPlanner ( )
inlinevirtual

Virtual destructor for the interface.

Definition at line 86 of file base_global_planner.h.

nav_core::BaseGlobalPlanner::BaseGlobalPlanner ( )
inlineprotected

Definition at line 89 of file base_global_planner.h.

Member Function Documentation

virtual void nav_core::BaseGlobalPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
)
pure virtual

Initialization function for the BaseGlobalPlanner.

Parameters
nameThe name of this planner
costmap_rosA pointer to the ROS wrapper of the costmap to use for planning
virtual bool nav_core::BaseGlobalPlanner::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan 
)
pure virtual

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

Parameters
startThe start pose
goalThe goal pose
planThe plan... filled by the planner
Returns
True if a valid plan was found, false otherwise
virtual bool nav_core::BaseGlobalPlanner::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
std::vector< geometry_msgs::PoseStamped > &  plan,
double &  cost 
)
inlinevirtual

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

Parameters
startThe start pose
goalThe goal pose
planThe plan... filled by the planner
costThe plans calculated cost
Returns
True if a valid plan was found, false otherwise

Definition at line 68 of file base_global_planner.h.


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


nav_core
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:23