Go to the documentation of this file.
37 #ifndef NAV_CORE_BASE_LOCAL_PLANNER_H
38 #define NAV_CORE_BASE_LOCAL_PLANNER_H
40 #include <geometry_msgs/PoseStamped.h>
41 #include <geometry_msgs/Twist.h>
50 class BaseLocalPlanner{
70 virtual bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& plan) = 0;
90 #endif // NAV_CORE_BASE_LOCAL_PLANNER_H
virtual void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)=0
Constructs the local planner.
virtual ~BaseLocalPlanner()
Virtual destructor for the interface.
virtual bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)=0
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
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.
nav_core
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:21