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. | |
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. | |
virtual void | setGoalPose (const nav_2d_msgs::Pose2DStamped &goal_pose)=0 |
Sets the global goal for this local planner. | |
virtual void | setPlan (const nav_2d_msgs::Path2D &path)=0 |
Sets the global plan for this local planner. | |
virtual | ~LocalPlanner () |
Virtual Destructor. |
Provides an interface for local planners used in navigation.
Definition at line 52 of file local_planner.h.
virtual nav_core2::LocalPlanner::~LocalPlanner | ( | ) | [inline, virtual] |
Virtual Destructor.
Definition at line 58 of file local_planner.h.
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.
pose | Current robot pose |
velocity | Current robot 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.
parent | NodeHandle to derive other NodeHandles from |
name | The name to give this instance of the local planner |
tf | A pointer to a transform listener |
costmap | A 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.
query_pose | The pose to check, in local costmap coordinates. |
velocity | Velocity to check |
virtual void nav_core2::LocalPlanner::setGoalPose | ( | const nav_2d_msgs::Pose2DStamped & | goal_pose | ) | [pure virtual] |
Sets the global goal for this local planner.
goal_pose | The Goal Pose |
virtual void nav_core2::LocalPlanner::setPlan | ( | const nav_2d_msgs::Path2D & | path | ) | [pure virtual] |
Sets the global plan for this local planner.
path | The global plan |