34 #ifndef NAV_CORE2_LOCAL_PLANNER_H    35 #define NAV_CORE2_LOCAL_PLANNER_H    39 #include <nav_2d_msgs/Path2D.h>    40 #include <nav_2d_msgs/Pose2DStamped.h>    41 #include <nav_2d_msgs/Twist2D.h>    42 #include <nav_2d_msgs/Twist2DStamped.h>    78   virtual void setGoalPose(
const nav_2d_msgs::Pose2DStamped& goal_pose) = 0;
    85   virtual void setPlan(
const nav_2d_msgs::Path2D& path) = 0;
    98                                                               const nav_2d_msgs::Twist2D& velocity) = 0;
   109   virtual bool isGoalReached(
const nav_2d_msgs::Pose2DStamped& pose, 
const nav_2d_msgs::Twist2D& velocity) = 0;
   113 #endif  // NAV_CORE2_LOCAL_PLANNER_H virtual void setPlan(const nav_2d_msgs::Path2D &path)=0
Sets the global plan for this local planner. 
virtual nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity)=0
Compute the best command given the current pose, velocity and goal. 
virtual ~LocalPlanner()
Virtual Destructor. 
virtual void setGoalPose(const nav_2d_msgs::Pose2DStamped &goal_pose)=0
Sets the global goal for this local planner. 
virtual void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, Costmap::Ptr costmap)=0
Constructs the local planner. 
virtual bool isGoalReached(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity)=0
Check to see whether the robot has reached its goal. 
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr
Provides an interface for local planners used in navigation.