Provides an interface for global planners used in navigation. More...
#include <global_planner.h>
| Public Member Functions | |
| virtual void | initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, Costmap::Ptr costmap)=0 | 
| Initialization function for the GlobalPlanner.  More... | |
| virtual nav_2d_msgs::Path2D | makePlan (const nav_2d_msgs::Pose2DStamped &start, const nav_2d_msgs::Pose2DStamped &goal)=0 | 
| Run the global planner to make a plan starting at the start and ending at the goal.  More... | |
| virtual | ~GlobalPlanner () | 
| Virtual Destructor.  More... | |
Provides an interface for global planners used in navigation.
Definition at line 50 of file global_planner.h.
| 
 | inlinevirtual | 
Virtual Destructor.
Definition at line 56 of file global_planner.h.
| 
 | pure virtual | 
Initialization function for the GlobalPlanner.
ROS parameters/topics are expected to be in the parent/name namespace. It is suggested that all NodeHandles in the planner use the parent NodeHandle's callback queue.
| parent | NodeHandle to derive other NodeHandles from | 
| name | The name of this planner | 
| tf | A pointer to a transform listener | 
| costmap | A pointer to the costmap | 
| 
 | pure virtual | 
Run the global planner to make a plan starting at the start and ending at the goal.
| start | The starting pose of the robot | 
| goal | The goal pose of the robot |