Nav2 Navigation Stack - humble  humble
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_util/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 rclcpp_lifecycle::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  nav2_util::declare_parameter_if_not_declared(
45  node,
46  plugin_name + ".xy_goal_tolerance", rclcpp::ParameterValue(0.25));
47  nav2_util::declare_parameter_if_not_declared(
48  node,
49  plugin_name + ".stateful", rclcpp::ParameterValue(true));
50 
51  node->get_parameter(plugin_name + ".xy_goal_tolerance", xy_goal_tolerance_);
52  node->get_parameter(plugin_name + ".stateful", stateful_);
53 
54  xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
55 
56  // Add callback for dynamic parameters
57  dyn_params_handler_ = node->add_on_set_parameters_callback(
58  std::bind(&PositionGoalChecker::dynamicParametersCallback, this, _1));
59 }
60 
61 void PositionGoalChecker::reset()
62 {
63  position_reached_ = false;
64 }
65 
66 bool PositionGoalChecker::isGoalReached(
67  const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
68  const geometry_msgs::msg::Twist &)
69 {
70  // If stateful and position was already reached, maintain state
71  if (stateful_ && position_reached_) {
72  return true;
73  }
74 
75  // Check if position is within tolerance
76  double dx = query_pose.position.x - goal_pose.position.x;
77  double dy = query_pose.position.y - goal_pose.position.y;
78 
79  bool position_reached = (dx * dx + dy * dy <= xy_goal_tolerance_sq_);
80 
81  // If stateful, remember that we reached the position
82  if (stateful_ && position_reached) {
83  position_reached_ = true;
84  }
85 
86  return position_reached;
87 }
88 
89 bool PositionGoalChecker::getTolerances(
90  geometry_msgs::msg::Pose & pose_tolerance,
91  geometry_msgs::msg::Twist & vel_tolerance)
92 {
93  double invalid_field = std::numeric_limits<double>::lowest();
94 
95  pose_tolerance.position.x = xy_goal_tolerance_;
96  pose_tolerance.position.y = xy_goal_tolerance_;
97  pose_tolerance.position.z = invalid_field;
98 
99  // Return zero orientation tolerance as we don't check it
100  pose_tolerance.orientation.x = 0.0;
101  pose_tolerance.orientation.y = 0.0;
102  pose_tolerance.orientation.z = 0.0;
103  pose_tolerance.orientation.w = 1.0;
104 
105  vel_tolerance.linear.x = invalid_field;
106  vel_tolerance.linear.y = invalid_field;
107  vel_tolerance.linear.z = invalid_field;
108 
109  vel_tolerance.angular.x = invalid_field;
110  vel_tolerance.angular.y = invalid_field;
111  vel_tolerance.angular.z = invalid_field;
112 
113  return true;
114 }
115 
117 {
118  xy_goal_tolerance_ = tolerance;
119  xy_goal_tolerance_sq_ = tolerance * tolerance;
120 }
121 
122 rcl_interfaces::msg::SetParametersResult
123 PositionGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
124 {
125  rcl_interfaces::msg::SetParametersResult result;
126  for (auto & parameter : parameters) {
127  const auto & type = parameter.get_type();
128  const auto & name = parameter.get_name();
129 
130  if (type == ParameterType::PARAMETER_DOUBLE) {
131  if (name == plugin_name_ + ".xy_goal_tolerance") {
132  xy_goal_tolerance_ = parameter.as_double();
133  xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
134  }
135  } else if (type == ParameterType::PARAMETER_BOOL) {
136  if (name == plugin_name_ + ".stateful") {
137  stateful_ = parameter.as_bool();
138  }
139  }
140  }
141  result.successful = true;
142  return result;
143 }
144 
145 } // namespace nav2_controller
146 
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.