Public Types | Public Member Functions | List of all members
dwb_local_planner::GoalChecker Class Referenceabstract

Function-object for checking whether a goal has been reached. More...

#include <goal_checker.h>

Public Types

using Ptr = std::shared_ptr< dwb_local_planner::GoalChecker >
 

Public Member Functions

virtual void initialize (const ros::NodeHandle &nh)=0
 Initialize any parameters from the NodeHandle. More...
 
virtual bool isGoalReached (const geometry_msgs::Pose2D &query_pose, const geometry_msgs::Pose2D &goal_pose, const nav_2d_msgs::Twist2D &velocity)=0
 Check whether the goal should be considered reached. More...
 
virtual void reset ()
 Reset the state of the goal checker (if any) More...
 
virtual ~GoalChecker ()
 

Detailed Description

Function-object for checking whether a goal has been reached.

This class defines the plugin interface for determining whether you have reached the goal state. This primarily consists of checking the relative positions of two poses (which are presumed to be in the same frame). It can also check the velocity, as some applications require that robot be stopped to be considered as having reached the goal.

Definition at line 54 of file goal_checker.h.

Member Typedef Documentation

Definition at line 57 of file goal_checker.h.

Constructor & Destructor Documentation

virtual dwb_local_planner::GoalChecker::~GoalChecker ( )
inlinevirtual

Definition at line 59 of file goal_checker.h.

Member Function Documentation

virtual void dwb_local_planner::GoalChecker::initialize ( const ros::NodeHandle nh)
pure virtual

Initialize any parameters from the NodeHandle.

Parameters
nhNodeHandle for grabbing parameters
virtual bool dwb_local_planner::GoalChecker::isGoalReached ( const geometry_msgs::Pose2D &  query_pose,
const geometry_msgs::Pose2D &  goal_pose,
const nav_2d_msgs::Twist2D &  velocity 
)
pure virtual

Check whether the goal should be considered reached.

Parameters
query_poseThe pose to check
goal_poseThe pose to check against
velocityThe robot's current velocity
Returns
True if goal is reached
virtual void dwb_local_planner::GoalChecker::reset ( )
inlinevirtual

Reset the state of the goal checker (if any)

Definition at line 70 of file goal_checker.h.


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


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:06:13