Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
kinematic_parameters.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 "dwb_plugins/kinematic_parameters.hpp"
36 
37 #include <memory>
38 #include <string>
39 #include <vector>
40 
41 #include "nav_2d_utils/parameters.hpp"
42 #include "nav2_util/node_utils.hpp"
43 #include "nav2_costmap_2d/costmap_filters/filter_values.hpp"
44 
45 using nav2_util::declare_parameter_if_not_declared;
46 using rcl_interfaces::msg::ParameterType;
47 using std::placeholders::_1;
48 
49 namespace dwb_plugins
50 {
51 
52 KinematicsHandler::KinematicsHandler()
53 {
54  kinematics_.store(new KinematicParameters);
55 }
56 
57 KinematicsHandler::~KinematicsHandler()
58 {
59  auto node = node_.lock();
60  if (dyn_params_handler_ && node) {
61  node->remove_on_set_parameters_callback(dyn_params_handler_.get());
62  }
63  dyn_params_handler_.reset();
64  delete kinematics_.load();
65 }
66 
67 void KinematicsHandler::initialize(
68  const nav2_util::LifecycleNode::SharedPtr & nh,
69  const std::string & plugin_name)
70 {
71  node_ = nh;
72  plugin_name_ = plugin_name;
73 
74  declare_parameter_if_not_declared(nh, plugin_name + ".min_vel_x", rclcpp::ParameterValue(0.0));
75  declare_parameter_if_not_declared(nh, plugin_name + ".min_vel_y", rclcpp::ParameterValue(0.0));
76  declare_parameter_if_not_declared(nh, plugin_name + ".max_vel_x", rclcpp::ParameterValue(0.0));
77  declare_parameter_if_not_declared(nh, plugin_name + ".max_vel_y", rclcpp::ParameterValue(0.0));
78  declare_parameter_if_not_declared(
79  nh, plugin_name + ".max_vel_theta",
80  rclcpp::ParameterValue(0.0));
81  declare_parameter_if_not_declared(
82  nh, plugin_name + ".min_speed_xy",
83  rclcpp::ParameterValue(0.0));
84  declare_parameter_if_not_declared(
85  nh, plugin_name + ".max_speed_xy",
86  rclcpp::ParameterValue(0.0));
87  declare_parameter_if_not_declared(
88  nh, plugin_name + ".min_speed_theta",
89  rclcpp::ParameterValue(0.0));
90  declare_parameter_if_not_declared(nh, plugin_name + ".acc_lim_x", rclcpp::ParameterValue(0.0));
91  declare_parameter_if_not_declared(nh, plugin_name + ".acc_lim_y", rclcpp::ParameterValue(0.0));
92  declare_parameter_if_not_declared(
93  nh, plugin_name + ".acc_lim_theta",
94  rclcpp::ParameterValue(0.0));
95  declare_parameter_if_not_declared(nh, plugin_name + ".decel_lim_x", rclcpp::ParameterValue(0.0));
96  declare_parameter_if_not_declared(nh, plugin_name + ".decel_lim_y", rclcpp::ParameterValue(0.0));
97  declare_parameter_if_not_declared(
98  nh, plugin_name + ".decel_lim_theta",
99  rclcpp::ParameterValue(0.0));
100 
101  KinematicParameters kinematics;
102 
103  nh->get_parameter(plugin_name + ".min_vel_x", kinematics.min_vel_x_);
104  nh->get_parameter(plugin_name + ".min_vel_y", kinematics.min_vel_y_);
105  nh->get_parameter(plugin_name + ".max_vel_x", kinematics.max_vel_x_);
106  nh->get_parameter(plugin_name + ".max_vel_y", kinematics.max_vel_y_);
107  nh->get_parameter(plugin_name + ".max_vel_theta", kinematics.max_vel_theta_);
108  nh->get_parameter(plugin_name + ".min_speed_xy", kinematics.min_speed_xy_);
109  nh->get_parameter(plugin_name + ".max_speed_xy", kinematics.max_speed_xy_);
110  nh->get_parameter(plugin_name + ".min_speed_theta", kinematics.min_speed_theta_);
111  nh->get_parameter(plugin_name + ".acc_lim_x", kinematics.acc_lim_x_);
112  nh->get_parameter(plugin_name + ".acc_lim_y", kinematics.acc_lim_y_);
113  nh->get_parameter(plugin_name + ".acc_lim_theta", kinematics.acc_lim_theta_);
114  nh->get_parameter(plugin_name + ".decel_lim_x", kinematics.decel_lim_x_);
115  nh->get_parameter(plugin_name + ".decel_lim_y", kinematics.decel_lim_y_);
116  nh->get_parameter(plugin_name + ".decel_lim_theta", kinematics.decel_lim_theta_);
117 
118  kinematics.base_max_vel_x_ = kinematics.max_vel_x_;
119  kinematics.base_max_vel_y_ = kinematics.max_vel_y_;
120  kinematics.base_max_speed_xy_ = kinematics.max_speed_xy_;
121  kinematics.base_max_vel_theta_ = kinematics.max_vel_theta_;
122 
123  // Add callback for dynamic parameters
124  dyn_params_handler_ = nh->add_on_set_parameters_callback(
125  std::bind(&KinematicsHandler::dynamicParametersCallback, this, _1));
126 
127  kinematics.min_speed_xy_sq_ = kinematics.min_speed_xy_ * kinematics.min_speed_xy_;
128  kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
129 
130  update_kinematics(kinematics);
131 }
132 
133 void KinematicsHandler::setSpeedLimit(
134  const double & speed_limit, const bool & percentage)
135 {
136  KinematicParameters kinematics(*kinematics_.load());
137 
138  if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
139  // Restore default value
140  kinematics.max_speed_xy_ = kinematics.base_max_speed_xy_;
141  kinematics.max_vel_x_ = kinematics.base_max_vel_x_;
142  kinematics.max_vel_y_ = kinematics.base_max_vel_y_;
143  kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_;
144  } else {
145  if (percentage) {
146  // Speed limit is expressed in % from maximum speed of robot
147  kinematics.max_speed_xy_ = kinematics.base_max_speed_xy_ * speed_limit / 100.0;
148  kinematics.max_vel_x_ = kinematics.base_max_vel_x_ * speed_limit / 100.0;
149  kinematics.max_vel_y_ = kinematics.base_max_vel_y_ * speed_limit / 100.0;
150  kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_ * speed_limit / 100.0;
151  } else {
152  // Speed limit is expressed in absolute value
153  if (speed_limit < kinematics.base_max_speed_xy_) {
154  kinematics.max_speed_xy_ = speed_limit;
155  // Handling components and angular velocity changes:
156  // Max velocities are being changed in the same proportion
157  // as absolute linear speed changed in order to preserve
158  // robot moving trajectories to be the same after speed change.
159  const double ratio = speed_limit / kinematics.base_max_speed_xy_;
160  kinematics.max_vel_x_ = kinematics.base_max_vel_x_ * ratio;
161  kinematics.max_vel_y_ = kinematics.base_max_vel_y_ * ratio;
162  kinematics.max_vel_theta_ = kinematics.base_max_vel_theta_ * ratio;
163  }
164  }
165  }
166 
167  // Do not forget to update max_speed_xy_sq_ as well
168  kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
169 
170  update_kinematics(kinematics);
171 }
172 
173 rcl_interfaces::msg::SetParametersResult
174 KinematicsHandler::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
175 {
176  rcl_interfaces::msg::SetParametersResult result;
177  KinematicParameters kinematics(*kinematics_.load());
178 
179  for (auto parameter : parameters) {
180  const auto & type = parameter.get_type();
181  const auto & name = parameter.get_name();
182 
183  if (type == ParameterType::PARAMETER_DOUBLE) {
184  if (name == plugin_name_ + ".min_vel_x") {
185  kinematics.min_vel_x_ = parameter.as_double();
186  } else if (name == plugin_name_ + ".min_vel_y") {
187  kinematics.min_vel_y_ = parameter.as_double();
188  } else if (name == plugin_name_ + ".max_vel_x") {
189  kinematics.max_vel_x_ = parameter.as_double();
190  kinematics.base_max_vel_x_ = kinematics.max_vel_x_;
191  } else if (name == plugin_name_ + ".max_vel_y") {
192  kinematics.max_vel_y_ = parameter.as_double();
193  kinematics.base_max_vel_y_ = kinematics.max_vel_y_;
194  } else if (name == plugin_name_ + ".max_vel_theta") {
195  kinematics.max_vel_theta_ = parameter.as_double();
196  kinematics.base_max_vel_theta_ = kinematics.max_vel_theta_;
197  } else if (name == plugin_name_ + ".min_speed_xy") {
198  kinematics.min_speed_xy_ = parameter.as_double();
199  kinematics.min_speed_xy_sq_ = kinematics.min_speed_xy_ * kinematics.min_speed_xy_;
200  } else if (name == plugin_name_ + ".max_speed_xy") {
201  kinematics.max_speed_xy_ = parameter.as_double();
202  kinematics.base_max_speed_xy_ = kinematics.max_speed_xy_;
203  } else if (name == plugin_name_ + ".min_speed_theta") {
204  kinematics.min_speed_theta_ = parameter.as_double();
205  kinematics.max_speed_xy_sq_ = kinematics.max_speed_xy_ * kinematics.max_speed_xy_;
206  } else if (name == plugin_name_ + ".acc_lim_x") {
207  kinematics.acc_lim_x_ = parameter.as_double();
208  } else if (name == plugin_name_ + ".acc_lim_y") {
209  kinematics.acc_lim_y_ = parameter.as_double();
210  } else if (name == plugin_name_ + ".acc_lim_theta") {
211  kinematics.acc_lim_theta_ = parameter.as_double();
212  } else if (name == plugin_name_ + ".decel_lim_x") {
213  kinematics.decel_lim_x_ = parameter.as_double();
214  } else if (name == plugin_name_ + ".decel_lim_y") {
215  kinematics.decel_lim_y_ = parameter.as_double();
216  } else if (name == plugin_name_ + ".decel_lim_theta") {
217  kinematics.decel_lim_theta_ = parameter.as_double();
218  }
219  }
220  }
221  update_kinematics(kinematics);
222  result.successful = true;
223  return result;
224 }
225 
226 void KinematicsHandler::update_kinematics(KinematicParameters kinematics)
227 {
228  delete kinematics_.load();
229  kinematics_.store(new KinematicParameters(kinematics));
230 }
231 
232 } // namespace dwb_plugins
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
A struct containing one representation of the robot's kinematics.