Public Member Functions | List of all members
nav_core2::LocalPlanner Class Referenceabstract

Provides an interface for local planners used in navigation. More...

#include <local_planner.h>

Public Member Functions

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. More...
 
virtual void initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, Costmap::Ptr costmap)=0
 Constructs the local planner. More...
 
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. More...
 
virtual void setGoalPose (const nav_2d_msgs::Pose2DStamped &goal_pose)=0
 Sets the global goal for this local planner. More...
 
virtual void setPlan (const nav_2d_msgs::Path2D &path)=0
 Sets the global plan for this local planner. More...
 
virtual ~LocalPlanner ()
 Virtual Destructor. More...
 

Detailed Description

Provides an interface for local planners used in navigation.

Definition at line 52 of file local_planner.h.

Constructor & Destructor Documentation

virtual nav_core2::LocalPlanner::~LocalPlanner ( )
inlinevirtual

Virtual Destructor.

Definition at line 58 of file local_planner.h.

Member Function Documentation

virtual nav_2d_msgs::Twist2DStamped nav_core2::LocalPlanner::computeVelocityCommands ( const nav_2d_msgs::Pose2DStamped &  pose,
const nav_2d_msgs::Twist2D &  velocity 
)
pure virtual

Compute the best command given the current pose, velocity and goal.

Get the local plan, given an initial pose, velocity and goal pose. It is presumed that the global plan is already set.

Parameters
poseCurrent robot pose
velocityCurrent robot velocity
Returns
The best computed velocity
virtual void nav_core2::LocalPlanner::initialize ( const ros::NodeHandle parent,
const std::string &  name,
TFListenerPtr  tf,
Costmap::Ptr  costmap 
)
pure virtual

Constructs the local planner.

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.

Parameters
parentNodeHandle to derive other NodeHandles from
nameThe name to give this instance of the local planner
tfA pointer to a transform listener
costmapA pointer to the costmap
virtual bool nav_core2::LocalPlanner::isGoalReached ( const nav_2d_msgs::Pose2DStamped &  pose,
const nav_2d_msgs::Twist2D &  velocity 
)
pure virtual

Check to see whether the robot has reached its goal.

This tests whether the robot has fully reached the goal, given the current pose and velocity.

Parameters
query_poseThe pose to check, in local costmap coordinates.
velocityVelocity to check
Returns
True if the goal conditions have been met
virtual void nav_core2::LocalPlanner::setGoalPose ( const nav_2d_msgs::Pose2DStamped &  goal_pose)
pure virtual

Sets the global goal for this local planner.

Parameters
goal_poseThe Goal Pose
virtual void nav_core2::LocalPlanner::setPlan ( const nav_2d_msgs::Path2D &  path)
pure virtual

Sets the global plan for this local planner.

Parameters
pathThe global plan

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


nav_core2
Author(s):
autogenerated on Wed Jun 26 2019 20:06:06