Provides an interface for local planners used in navigation. All local planners written as plugins for the navigation stack must adhere to this interface. More...
#include <base_local_planner.h>
Public Member Functions | |
virtual bool | computeVelocityCommands (geometry_msgs::Twist &cmd_vel)=0 |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base. | |
virtual void | initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)=0 |
Constructs the local planner. | |
virtual bool | isGoalReached ()=0 |
Check if the goal pose has been achieved by the local planner. | |
virtual bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &plan)=0 |
Set the plan that the local planner is following. | |
virtual | ~BaseLocalPlanner () |
Virtual destructor for the interface. | |
Protected Member Functions | |
BaseLocalPlanner () |
Provides an interface for local planners used in navigation. All local planners written as plugins for the navigation stack must adhere to this interface.
Definition at line 50 of file base_local_planner.h.
virtual nav_core::BaseLocalPlanner::~BaseLocalPlanner | ( | ) | [inline, virtual] |
Virtual destructor for the interface.
Definition at line 83 of file base_local_planner.h.
nav_core::BaseLocalPlanner::BaseLocalPlanner | ( | ) | [inline, protected] |
Definition at line 86 of file base_local_planner.h.
virtual bool nav_core::BaseLocalPlanner::computeVelocityCommands | ( | geometry_msgs::Twist & | cmd_vel | ) | [pure virtual] |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
virtual void nav_core::BaseLocalPlanner::initialize | ( | std::string | name, |
tf::TransformListener * | tf, | ||
costmap_2d::Costmap2DROS * | costmap_ros | ||
) | [pure virtual] |
Constructs the local planner.
name | The name to give this instance of the local planner |
tf | A pointer to a transform listener |
costmap | The cost map to use for assigning costs to local plans |
virtual bool nav_core::BaseLocalPlanner::isGoalReached | ( | ) | [pure virtual] |
Check if the goal pose has been achieved by the local planner.
virtual bool nav_core::BaseLocalPlanner::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | plan | ) | [pure virtual] |
Set the plan that the local planner is following.
orig_global_plan | The plan to pass to the local planner |