Goal Checker plugin that checks the position difference and velocity. More...
#include <stopped_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 |
StoppedGoalChecker () | |
Public Member Functions inherited from dwb_plugins::SimpleGoalChecker | |
void | reset () override |
SimpleGoalChecker () | |
Public Member Functions inherited from dwb_local_planner::GoalChecker | |
virtual | ~GoalChecker () |
Protected Attributes | |
double | rot_stopped_velocity_ |
double | trans_stopped_velocity_ |
Protected Attributes inherited from dwb_plugins::SimpleGoalChecker | |
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 checks the position difference and velocity.
Definition at line 48 of file stopped_goal_checker.h.
dwb_plugins::StoppedGoalChecker::StoppedGoalChecker | ( | ) |
Definition at line 41 of file stopped_goal_checker.cpp.
|
overridevirtual |
Reimplemented from dwb_plugins::SimpleGoalChecker.
Definition at line 46 of file stopped_goal_checker.cpp.
|
overridevirtual |
Reimplemented from dwb_plugins::SimpleGoalChecker.
Definition at line 53 of file stopped_goal_checker.cpp.
|
protected |
Definition at line 57 of file stopped_goal_checker.h.
|
protected |
Definition at line 57 of file stopped_goal_checker.h.