Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
stopped_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 <cmath>
36 #include <string>
37 #include <memory>
38 #include <limits>
39 #include <vector>
40 #include "nav2_controller/plugins/stopped_goal_checker.hpp"
41 #include "pluginlib/class_list_macros.hpp"
42 #include "nav2_ros_common/node_utils.hpp"
43 
44 using std::hypot;
45 using std::fabs;
46 
47 using rcl_interfaces::msg::ParameterType;
48 using std::placeholders::_1;
49 
50 namespace nav2_controller
51 {
52 
53 StoppedGoalChecker::StoppedGoalChecker()
54 : SimpleGoalChecker(), rot_stopped_velocity_(0.25), trans_stopped_velocity_(0.25)
55 {
56 }
57 
58 void StoppedGoalChecker::initialize(
59  const nav2::LifecycleNode::WeakPtr & parent,
60  const std::string & plugin_name,
61  const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
62 {
63  plugin_name_ = plugin_name;
64  SimpleGoalChecker::initialize(parent, plugin_name, costmap_ros);
65 
66  auto node = parent.lock();
67 
68  rot_stopped_velocity_ = node->declare_or_get_parameter(
69  plugin_name + ".rot_stopped_velocity", 0.25);
70  trans_stopped_velocity_ = node->declare_or_get_parameter(
71  plugin_name + ".trans_stopped_velocity", 0.25);
72 
73  // Add callback for dynamic parameters
74  dyn_params_handler_ = node->add_on_set_parameters_callback(
75  std::bind(&StoppedGoalChecker::dynamicParametersCallback, this, _1));
76 }
77 
78 bool StoppedGoalChecker::isGoalReached(
79  const geometry_msgs::msg::Pose & query_pose, const geometry_msgs::msg::Pose & goal_pose,
80  const geometry_msgs::msg::Twist & velocity)
81 {
82  bool ret = SimpleGoalChecker::isGoalReached(query_pose, goal_pose, velocity);
83  if (!ret) {
84  return ret;
85  }
86 
87  return fabs(velocity.angular.z) <= rot_stopped_velocity_ &&
88  hypot(velocity.linear.x, velocity.linear.y) <= trans_stopped_velocity_;
89 }
90 
91 bool StoppedGoalChecker::getTolerances(
92  geometry_msgs::msg::Pose & pose_tolerance,
93  geometry_msgs::msg::Twist & vel_tolerance)
94 {
95  double invalid_field = std::numeric_limits<double>::lowest();
96 
97  // populate the poses
98  bool rtn = SimpleGoalChecker::getTolerances(pose_tolerance, vel_tolerance);
99 
100  // override the velocities
101  vel_tolerance.linear.x = trans_stopped_velocity_;
102  vel_tolerance.linear.y = trans_stopped_velocity_;
103  vel_tolerance.linear.z = invalid_field;
104 
105  vel_tolerance.angular.x = invalid_field;
106  vel_tolerance.angular.y = invalid_field;
107  vel_tolerance.angular.z = rot_stopped_velocity_;
108 
109  return true && rtn;
110 }
111 
112 rcl_interfaces::msg::SetParametersResult
113 StoppedGoalChecker::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
114 {
115  rcl_interfaces::msg::SetParametersResult result;
116  for (auto parameter : parameters) {
117  const auto & param_type = parameter.get_type();
118  const auto & param_name = parameter.get_name();
119  if (param_name.find(plugin_name_ + ".") != 0) {
120  continue;
121  }
122 
123  if (param_type == ParameterType::PARAMETER_DOUBLE) {
124  if (param_name == plugin_name_ + ".rot_stopped_velocity") {
125  rot_stopped_velocity_ = parameter.as_double();
126  } else if (param_name == plugin_name_ + ".trans_stopped_velocity") {
127  trans_stopped_velocity_ = parameter.as_double();
128  }
129  }
130  }
131  result.successful = true;
132  return result;
133 }
134 
135 } // namespace nav2_controller
136 
Goal Checker plugin that checks the position difference and velocity.
Function-object for checking whether a goal has been reached.