Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Types | Public Member Functions | List of all members
nav2_core::GoalChecker Class Referenceabstract

Function-object for checking whether a goal has been reached. More...

#include <nav2_core/include/nav2_core/goal_checker.hpp>

Inheritance diagram for nav2_core::GoalChecker:
Inheritance graph
[legend]

Public Types

typedef std::shared_ptr< nav2_core::GoalCheckerPtr
 

Public Member Functions

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. More...
 
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. More...
 
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). More...
 

Detailed Description

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.

Definition at line 61 of file goal_checker.hpp.

Member Function Documentation

◆ getTolerances()

virtual bool nav2_core::GoalChecker::getTolerances ( geometry_msgs::msg::Pose &  pose_tolerance,
geometry_msgs::msg::Twist &  vel_tolerance 
)
pure virtual

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_toleranceThe tolerance used for checking in Pose fields
vel_toleranceThe tolerance used for checking velocity fields
Returns
True if the tolerances are valid to use

Implemented in nav2_controller::StoppedGoalChecker, nav2_controller::SimpleGoalChecker, and nav2_controller::PositionGoalChecker.

Referenced by nav2_regulated_pure_pursuit_controller::RegulatedPurePursuitController::computeVelocityCommands(), nav2_rotation_shim_controller::RotationShimController::computeVelocityCommands(), and nav2_graceful_controller::GracefulController::computeVelocityCommands().

Here is the caller graph for this function:

◆ initialize()

virtual void nav2_core::GoalChecker::initialize ( const rclcpp_lifecycle::LifecycleNode::WeakPtr &  parent,
const std::string &  plugin_name,
const std::shared_ptr< nav2_costmap_2d::Costmap2DROS costmap_ros 
)
pure virtual

Initialize any parameters from the NodeHandle.

Parameters
parentNode pointer for grabbing parameters

Implemented in nav2_controller::StoppedGoalChecker, nav2_controller::SimpleGoalChecker, and nav2_controller::PositionGoalChecker.

◆ isGoalReached()

virtual bool nav2_core::GoalChecker::isGoalReached ( const geometry_msgs::msg::Pose &  query_pose,
const geometry_msgs::msg::Pose &  goal_pose,
const geometry_msgs::msg::Twist &  velocity 
)
pure virtual

Check whether the goal should be considered reached.

Parameters
query_poseThe pose to check
goal_poseThe pose to check against
velocityThe robot's current velocity
Returns
True if goal is reached

Implemented in nav2_controller::StoppedGoalChecker, nav2_controller::SimpleGoalChecker, and nav2_controller::PositionGoalChecker.


The documentation for this class was generated from the following file: