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 () | |
Protected Attributes | |
| double | rot_stopped_velocity_ |
| double | trans_stopped_velocity_ |
Goal Checker plugin that checks the position difference and velocity.
Definition at line 48 of file stopped_goal_checker.h.
Definition at line 41 of file stopped_goal_checker.cpp.
| void dwb_plugins::StoppedGoalChecker::initialize | ( | const ros::NodeHandle & | nh | ) | [override, virtual] |
Reimplemented from dwb_plugins::SimpleGoalChecker.
Definition at line 46 of file stopped_goal_checker.cpp.
| bool dwb_plugins::StoppedGoalChecker::isGoalReached | ( | const geometry_msgs::Pose2D & | query_pose, |
| const geometry_msgs::Pose2D & | goal_pose, | ||
| const nav_2d_msgs::Twist2D & | velocity | ||
| ) | [override, virtual] |
Reimplemented from dwb_plugins::SimpleGoalChecker.
Definition at line 53 of file stopped_goal_checker.cpp.
double dwb_plugins::StoppedGoalChecker::rot_stopped_velocity_ [protected] |
Definition at line 57 of file stopped_goal_checker.h.
double dwb_plugins::StoppedGoalChecker::trans_stopped_velocity_ [protected] |
Definition at line 57 of file stopped_goal_checker.h.