Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
position_goal_checker.hpp
1 // Copyright (c) 2025 Prabhav Saxena
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_CONTROLLER__PLUGINS__POSITION_GOAL_CHECKER_HPP_
16 #define NAV2_CONTROLLER__PLUGINS__POSITION_GOAL_CHECKER_HPP_
17 
18 #include <string>
19 #include <memory>
20 #include <vector>
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_ros_common/lifecycle_node.hpp"
23 #include "nav2_core/goal_checker.hpp"
24 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
25 
26 namespace nav2_controller
27 {
28 
34 {
35 public:
37  ~PositionGoalChecker() override = default;
38 
39  void initialize(
40  const nav2::LifecycleNode::WeakPtr & parent,
41  const std::string & plugin_name,
42  const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override;
43 
44  void reset() override;
45 
46  bool isGoalReached(
47  const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
48  const geometry_msgs::msg::Twist & velocity) override;
49 
50  bool getTolerances(
51  geometry_msgs::msg::Pose & pose_tolerance,
52  geometry_msgs::msg::Twist & vel_tolerance) override;
53 
58  void setXYGoalTolerance(double tolerance);
59 
60 protected:
61  double xy_goal_tolerance_;
62  double xy_goal_tolerance_sq_;
63  bool stateful_;
64  bool position_reached_;
65  std::string plugin_name_;
66  rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
67 
72  rcl_interfaces::msg::SetParametersResult
73  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
74 };
75 
76 } // namespace nav2_controller
77 
78 #endif // NAV2_CONTROLLER__PLUGINS__POSITION_GOAL_CHECKER_HPP_
Goal Checker plugin that only checks XY position, ignoring orientation.
void setXYGoalTolerance(double tolerance)
Set the XY goal tolerance.
bool getTolerances(geometry_msgs::msg::Pose &pose_tolerance, geometry_msgs::msg::Twist &vel_tolerance) override
Get the maximum possible tolerances used for goal checking in the major types. Any field without a va...
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
bool isGoalReached(const geometry_msgs::msg::Pose &query_pose, const geometry_msgs::msg::Pose &goal_pose, const geometry_msgs::msg::Twist &velocity) override
Check whether the goal should be considered reached.
void initialize(const nav2::LifecycleNode::WeakPtr &parent, const std::string &plugin_name, const std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
Initialize any parameters from the NodeHandle.
Function-object for checking whether a goal has been reached.