$search
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. | |
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. | |
virtual | ~BaseGlobalPlanner () |
Virtual destructor for the interface. | |
Protected Member Functions | |
BaseGlobalPlanner () |
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 | ( | ) | [inline, virtual] |
Virtual destructor for the interface.
Definition at line 70 of file base_global_planner.h.
nav_core::BaseGlobalPlanner::BaseGlobalPlanner | ( | ) | [inline, protected] |
Definition at line 73 of file base_global_planner.h.
virtual void nav_core::BaseGlobalPlanner::initialize | ( | std::string | name, | |
costmap_2d::Costmap2DROS * | costmap_ros | |||
) | [pure virtual] |
Initialization function for the BaseGlobalPlanner.
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.
start | The start pose | |
goal | The goal pose | |
plan | The plan... filled by the planner |