43 xy_goal_tolerance_(0.25), yaw_goal_tolerance_(0.25), stateful_(true), check_xy_(true), xy_goal_tolerance_sq_(0.0625)
61 const nav_2d_msgs::Twist2D& velocity)
65 double dx = query_pose.x - goal_pose.x,
66 dy = query_pose.y - goal_pose.y;
double xy_goal_tolerance_sq_
double yaw_goal_tolerance_
Goal Checker plugin that only checks the position difference.
void initialize(const ros::NodeHandle &nh) override
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
double xy_goal_tolerance_
bool isGoalReached(const geometry_msgs::Pose2D &query_pose, const geometry_msgs::Pose2D &goal_pose, const nav_2d_msgs::Twist2D &velocity) override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
def shortest_angular_distance(from_angle, to_angle)