Class GoalChecker

Class Documentation

class 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.

Public Types

typedef std::shared_ptr<nav2_core::GoalChecker> Ptr

Public Functions

inline virtual ~GoalChecker()
virtual void initialize(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name, const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) = 0

Initialize any parameters from the NodeHandle.

Parameters:

parent – Node pointer for grabbing parameters

virtual void reset() = 0
virtual bool isGoalReached(const geometry_msgs::msg::Pose &query_pose, const geometry_msgs::msg::Pose &goal_pose, const geometry_msgs::msg::Twist &velocity) = 0

Check whether the goal should be considered reached.

Parameters:
  • query_pose – The pose to check

  • goal_pose – The pose to check against

  • velocity – The robot’s current velocity

Returns:

True if goal is reached

virtual bool getTolerances(geometry_msgs::msg::Pose &pose_tolerance, geometry_msgs::msg::Twist &vel_tolerance) = 0

Get the maximum possible tolerances used for goal checking in the major types. Any field without a valid entry is replaced with std::numeric_limits<double>::lowest() to indicate that it is not measured. For tolerance across multiple entries (e.x. XY tolerances), both fields will contain this value since it is the maximum tolerance that each independent field could be assuming the other has no error (e.x. X and Y).

Parameters:
  • pose_tolerance – The tolerance used for checking in Pose fields

  • vel_tolerance – The tolerance used for checking velocity fields

Returns:

True if the tolerances are valid to use