Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
simple_goal_checker.cpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include <memory>
36 #include <string>
37 #include <limits>
38 #include <vector>
39 #include "nav2_controller/plugins/simple_goal_checker.hpp"
40 #include "pluginlib/class_list_macros.hpp"
41 #include "angles/angles.h"
42 #include "nav2_ros_common/node_utils.hpp"
43 #include "nav2_util/geometry_utils.hpp"
44 #pragma GCC diagnostic push
45 #pragma GCC diagnostic ignored "-Wpedantic"
46 #include "tf2/utils.hpp"
47 #pragma GCC diagnostic pop
48 
49 using rcl_interfaces::msg::ParameterType;
50 using std::placeholders::_1;
51 
52 namespace nav2_controller
53 {
54 
55 SimpleGoalChecker::SimpleGoalChecker()
56 : xy_goal_tolerance_(0.25),
57  yaw_goal_tolerance_(0.25),
58  stateful_(true),
59  check_xy_(true),
60  xy_goal_tolerance_sq_(0.0625)
61 {
62 }
63 
64 void SimpleGoalChecker::initialize(
65  const nav2::LifecycleNode::WeakPtr & parent,
66  const std::string & plugin_name,
67  const std::shared_ptr<nav2_costmap_2d::Costmap2DROS>/*costmap_ros*/)
68 {
69  plugin_name_ = plugin_name;
70  auto node = parent.lock();
71 
72  nav2::declare_parameter_if_not_declared(
73  node,
74  plugin_name + ".xy_goal_tolerance", rclcpp::ParameterValue(0.25));
75  nav2::declare_parameter_if_not_declared(
76  node,
77  plugin_name + ".yaw_goal_tolerance", rclcpp::ParameterValue(0.25));
78  nav2::declare_parameter_if_not_declared(
79  node,
80  plugin_name + ".stateful", rclcpp::ParameterValue(true));
81 
82  node->get_parameter(plugin_name + ".xy_goal_tolerance", xy_goal_tolerance_);
83  node->get_parameter(plugin_name + ".yaw_goal_tolerance", yaw_goal_tolerance_);
84  node->get_parameter(plugin_name + ".stateful", stateful_);
85 
86  xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
87 
88  // Add callback for dynamic parameters
89  dyn_params_handler_ = node->add_on_set_parameters_callback(
90  std::bind(&SimpleGoalChecker::dynamicParametersCallback, this, _1));
91 }
92 
93 void SimpleGoalChecker::reset()
94 {
95  check_xy_ = true;
96 }
97 
98 bool SimpleGoalChecker::isGoalReached(
99  const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
100  const geometry_msgs::msg::Twist &)
101 {
102  if (check_xy_) {
103  double dx = query_pose.position.x - goal_pose.position.x,
104  dy = query_pose.position.y - goal_pose.position.y;
105  if (dx * dx + dy * dy > xy_goal_tolerance_sq_) {
106  return false;
107  }
108  // We are within the window
109  // If we are stateful, change the state.
110  if (stateful_) {
111  check_xy_ = false;
112  }
113  }
114  double dyaw = angles::shortest_angular_distance(
115  tf2::getYaw(query_pose.orientation),
116  tf2::getYaw(goal_pose.orientation));
117  return fabs(dyaw) <= yaw_goal_tolerance_;
118 }
119 
120 bool SimpleGoalChecker::getTolerances(
121  geometry_msgs::msg::Pose & pose_tolerance,
122  geometry_msgs::msg::Twist & vel_tolerance)
123 {
124  double invalid_field = std::numeric_limits<double>::lowest();
125 
126  pose_tolerance.position.x = xy_goal_tolerance_;
127  pose_tolerance.position.y = xy_goal_tolerance_;
128  pose_tolerance.position.z = invalid_field;
129  pose_tolerance.orientation =
130  nav2_util::geometry_utils::orientationAroundZAxis(yaw_goal_tolerance_);
131 
132  vel_tolerance.linear.x = invalid_field;
133  vel_tolerance.linear.y = invalid_field;
134  vel_tolerance.linear.z = invalid_field;
135 
136  vel_tolerance.angular.x = invalid_field;
137  vel_tolerance.angular.y = invalid_field;
138  vel_tolerance.angular.z = invalid_field;
139 
140  return true;
141 }
142 
143 rcl_interfaces::msg::SetParametersResult
144 SimpleGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
145 {
146  rcl_interfaces::msg::SetParametersResult result;
147  for (auto & parameter : parameters) {
148  const auto & param_type = parameter.get_type();
149  const auto & param_name = parameter.get_name();
150  if (param_name.find(plugin_name_ + ".") != 0) {
151  continue;
152  }
153  if (param_type == ParameterType::PARAMETER_DOUBLE) {
154  if (param_name == plugin_name_ + ".xy_goal_tolerance") {
155  xy_goal_tolerance_ = parameter.as_double();
156  xy_goal_tolerance_sq_ = xy_goal_tolerance_ * xy_goal_tolerance_;
157  } else if (param_name == plugin_name_ + ".yaw_goal_tolerance") {
158  yaw_goal_tolerance_ = parameter.as_double();
159  }
160  } else if (param_type == ParameterType::PARAMETER_BOOL) {
161  if (param_name == plugin_name_ + ".stateful") {
162  stateful_ = parameter.as_bool();
163  }
164  }
165  }
166  result.successful = true;
167  return result;
168 }
169 
170 } // namespace nav2_controller
171 
Goal Checker plugin that only checks the position difference.
Function-object for checking whether a goal has been reached.