Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
position_goal_checker.cpp
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 #include <memory>
16 #include <string>
17 #include <limits>
18 #include "nav2_controller/plugins/position_goal_checker.hpp"
19 #include "pluginlib/class_list_macros.hpp"
20 #include "nav2_ros_common/node_utils.hpp"
21 
22 using rcl_interfaces::msg::ParameterType;
23 using std::placeholders::_1;
24 
25 namespace nav2_controller
26 {
27 
28 PositionGoalChecker::PositionGoalChecker()
29 : xy_goal_tolerance_(0.25),
30  xy_goal_tolerance_sq_(0.0625),
31  stateful_(true),
32  position_reached_(false)
33 {
34 }
35 
36 void PositionGoalChecker::initialize(
37  const nav2::LifecycleNode::WeakPtr & parent,
38  const std::string & plugin_name,
39  const std::shared_ptr<nav2_costmap_2d::Costmap2DROS>/*costmap_ros*/)
40 {
41  plugin_name_ = plugin_name;
42  auto node = parent.lock();
43 
44  xy_goal_tolerance_ = node->declare_or_get_parameter(plugin_name + ".xy_goal_tolerance", 0.25);
45  stateful_ = node->declare_or_get_parameter(plugin_name + ".stateful", true);
46 
47  xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
48 
49  // Add callback for dynamic parameters
50  dyn_params_handler_ = node->add_on_set_parameters_callback(
51  std::bind(&PositionGoalChecker::dynamicParametersCallback, this, _1));
52 }
53 
54 void PositionGoalChecker::reset()
55 {
56  position_reached_ = false;
57 }
58 
59 bool PositionGoalChecker::isGoalReached(
60  const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
61  const geometry_msgs::msg::Twist &)
62 {
63  // If stateful and position was already reached, maintain state
64  if (stateful_ && position_reached_) {
65  return true;
66  }
67 
68  // Check if position is within tolerance
69  double dx = query_pose.position.x - goal_pose.position.x;
70  double dy = query_pose.position.y - goal_pose.position.y;
71 
72  bool position_reached = (dx * dx + dy * dy <= xy_goal_tolerance_sq_);
73 
74  // If stateful, remember that we reached the position
75  if (stateful_ && position_reached) {
76  position_reached_ = true;
77  }
78 
79  return position_reached;
80 }
81 
82 bool PositionGoalChecker::getTolerances(
83  geometry_msgs::msg::Pose & pose_tolerance,
84  geometry_msgs::msg::Twist & vel_tolerance)
85 {
86  double invalid_field = std::numeric_limits<double>::lowest();
87 
88  pose_tolerance.position.x = xy_goal_tolerance_;
89  pose_tolerance.position.y = xy_goal_tolerance_;
90  pose_tolerance.position.z = invalid_field;
91 
92  // Return zero orientation tolerance as we don't check it
93  pose_tolerance.orientation.x = 0.0;
94  pose_tolerance.orientation.y = 0.0;
95  pose_tolerance.orientation.z = 0.0;
96  pose_tolerance.orientation.w = 1.0;
97 
98  vel_tolerance.linear.x = invalid_field;
99  vel_tolerance.linear.y = invalid_field;
100  vel_tolerance.linear.z = invalid_field;
101 
102  vel_tolerance.angular.x = invalid_field;
103  vel_tolerance.angular.y = invalid_field;
104  vel_tolerance.angular.z = invalid_field;
105 
106  return true;
107 }
108 
110 {
111  xy_goal_tolerance_ = tolerance;
112  xy_goal_tolerance_sq_ = tolerance * tolerance;
113 }
114 
115 rcl_interfaces::msg::SetParametersResult
116 PositionGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
117 {
118  rcl_interfaces::msg::SetParametersResult result;
119  for (auto & parameter : parameters) {
120  const auto & param_type = parameter.get_type();
121  const auto & param_name = parameter.get_name();
122  if (param_name.find(plugin_name_ + ".") != 0) {
123  continue;
124  }
125 
126  if (param_type == ParameterType::PARAMETER_DOUBLE) {
127  if (param_name == plugin_name_ + ".xy_goal_tolerance") {
128  xy_goal_tolerance_ = parameter.as_double();
129  xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
130  }
131  } else if (param_type == ParameterType::PARAMETER_BOOL) {
132  if (param_name == plugin_name_ + ".stateful") {
133  stateful_ = parameter.as_bool();
134  }
135  }
136  }
137  result.successful = true;
138  return result;
139 }
140 
141 } // namespace nav2_controller
142 
Goal Checker plugin that only checks XY position, ignoring orientation.
void setXYGoalTolerance(double tolerance)
Set the XY goal tolerance.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Function-object for checking whether a goal has been reached.