35 #ifndef NAV2_CORE__GOAL_CHECKER_HPP_
36 #define NAV2_CORE__GOAL_CHECKER_HPP_
41 #include "rclcpp/rclcpp.hpp"
42 #include "rclcpp_lifecycle/lifecycle_node.hpp"
43 #include "geometry_msgs/msg/pose.hpp"
44 #include "geometry_msgs/msg/twist.hpp"
46 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
64 typedef std::shared_ptr<nav2_core::GoalChecker> Ptr;
73 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
74 const std::string & plugin_name,
75 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) = 0;
77 virtual void reset() = 0;
87 const geometry_msgs::msg::Pose & query_pose,
const geometry_msgs::msg::Pose & goal_pose,
88 const geometry_msgs::msg::Twist & velocity) = 0;
101 geometry_msgs::msg::Pose & pose_tolerance,
102 geometry_msgs::msg::Twist & vel_tolerance) = 0;
Function-object for checking whether a goal has been reached.
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.
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.
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 va...