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>
|
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...
|
|
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.
virtual nav_core::BaseGlobalPlanner::~BaseGlobalPlanner |
( |
| ) |
|
|
inlinevirtual |
nav_core::BaseGlobalPlanner::BaseGlobalPlanner |
( |
| ) |
|
|
inlineprotected |
Initialization function for the BaseGlobalPlanner.
- Parameters
-
name | The name of this planner |
costmap_ros | A 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
-
start | The start pose |
goal | The goal pose |
plan | The 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
-
start | The start pose |
goal | The goal pose |
plan | The plan... filled by the planner |
cost | The 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: