Goal Checker plugin that only checks the position difference. More...
#include <simple_goal_checker.h>
Public Member Functions | |
void | initialize (const ros::NodeHandle &nh) override |
bool | isGoalReached (const geometry_msgs::Pose2D &query_pose, const geometry_msgs::Pose2D &goal_pose, const nav_2d_msgs::Twist2D &velocity) override |
void | reset () override |
SimpleGoalChecker () | |
Public Member Functions inherited from dwb_local_planner::GoalChecker | |
virtual | ~GoalChecker () |
Protected Attributes | |
bool | check_xy_ |
bool | stateful_ |
double | xy_goal_tolerance_ |
double | xy_goal_tolerance_sq_ |
double | yaw_goal_tolerance_ |
Additional Inherited Members | |
Public Types inherited from dwb_local_planner::GoalChecker | |
typedef std::shared_ptr< dwb_local_planner::GoalChecker > | Ptr |
Goal Checker plugin that only checks the position difference.
This class can be stateful if the stateful parameter is set to true (which it is by default). This means that the goal checker will not check if the xy position matches again once it is found to be true.
Definition at line 51 of file simple_goal_checker.h.
dwb_plugins::SimpleGoalChecker::SimpleGoalChecker | ( | ) |
Definition at line 42 of file simple_goal_checker.cpp.
|
overridevirtual |
Implements dwb_local_planner::GoalChecker.
Reimplemented in dwb_plugins::StoppedGoalChecker.
Definition at line 47 of file simple_goal_checker.cpp.
|
overridevirtual |
Implements dwb_local_planner::GoalChecker.
Reimplemented in dwb_plugins::StoppedGoalChecker.
Definition at line 60 of file simple_goal_checker.cpp.
|
overridevirtual |
Reimplemented from dwb_local_planner::GoalChecker.
Definition at line 55 of file simple_goal_checker.cpp.
|
protected |
Definition at line 62 of file simple_goal_checker.h.
|
protected |
Definition at line 62 of file simple_goal_checker.h.
|
protected |
Definition at line 61 of file simple_goal_checker.h.
|
protected |
Definition at line 65 of file simple_goal_checker.h.
|
protected |
Definition at line 61 of file simple_goal_checker.h.