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

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. More...
 
virtual void initialize (std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)=0
 Constructs the local planner. More...
 
virtual bool isGoalReached ()=0
 Check if the goal pose has been achieved by the local planner. More...
 
virtual bool setPlan (const std::vector< geometry_msgs::PoseStamped > &plan)=0
 Set the plan that the local planner is following. More...
 
virtual ~BaseLocalPlanner ()
 Virtual destructor for the interface. More...
 

Protected Member Functions

 BaseLocalPlanner ()
 

Detailed Description

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.

Constructor & Destructor Documentation

virtual nav_core::BaseLocalPlanner::~BaseLocalPlanner ( )
inlinevirtual

Virtual destructor for the interface.

Definition at line 83 of file base_local_planner.h.

nav_core::BaseLocalPlanner::BaseLocalPlanner ( )
inlineprotected

Definition at line 86 of file base_local_planner.h.

Member Function Documentation

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.

Parameters
cmd_velWill be filled with the velocity command to be passed to the robot base
Returns
True if a valid velocity command was found, false otherwise
virtual void nav_core::BaseLocalPlanner::initialize ( std::string  name,
tf::TransformListener tf,
costmap_2d::Costmap2DROS costmap_ros 
)
pure virtual

Constructs the local planner.

Parameters
nameThe name to give this instance of the local planner
tfA pointer to a transform listener
costmap_rosThe 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.

Returns
True if achieved, false otherwise
virtual bool nav_core::BaseLocalPlanner::setPlan ( const std::vector< geometry_msgs::PoseStamped > &  plan)
pure virtual

Set the plan that the local planner is following.

Parameters
planThe plan to pass to the local planner
Returns
True if the plan was updated successfully, false otherwise

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


nav_core
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:47