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 () |
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 55 of file goal_checker.h.
using dwb_local_planner::GoalChecker::Ptr = std::shared_ptr<dwb_local_planner::GoalChecker> |
Definition at line 58 of file goal_checker.h.
|
inlinevirtual |
Definition at line 60 of file goal_checker.h.
|
pure virtual |
Initialize any parameters from the NodeHandle.
nh | NodeHandle for grabbing parameters |
|
pure virtual |
Check whether the goal should be considered reached.
query_pose | The pose to check |
goal_pose | The pose to check against |
velocity | The robot's current velocity |
|
inlinevirtual |
Reset the state of the goal checker (if any)
Definition at line 71 of file goal_checker.h.