Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
velocity_smoother.cpp
1 // Copyright (c) 2022 Samsung Research
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 <chrono>
16 #include <limits>
17 #include <memory>
18 #include <string>
19 #include <utility>
20 #include <vector>
21 
22 #include "nav2_velocity_smoother/velocity_smoother.hpp"
23 
24 using namespace std::chrono_literals;
25 using nav2_util::declare_parameter_if_not_declared;
26 using std::placeholders::_1;
27 using rcl_interfaces::msg::ParameterType;
28 
29 namespace nav2_velocity_smoother
30 {
31 
32 VelocitySmoother::VelocitySmoother(const rclcpp::NodeOptions & options)
33 : LifecycleNode("velocity_smoother", "", options),
34  last_command_time_{0, 0, get_clock()->get_clock_type()}
35 {
36 }
37 
39 {
40  if (timer_) {
41  timer_->cancel();
42  timer_.reset();
43  }
44 }
45 
46 nav2_util::CallbackReturn
47 VelocitySmoother::on_configure(const rclcpp_lifecycle::State &)
48 {
49  RCLCPP_INFO(get_logger(), "Configuring velocity smoother");
50  auto node = shared_from_this();
51  std::string feedback_type;
52  double velocity_timeout_dbl;
53 
54  // Smoothing metadata
55  declare_parameter_if_not_declared(node, "smoothing_frequency", rclcpp::ParameterValue(20.0));
56  declare_parameter_if_not_declared(
57  node, "feedback", rclcpp::ParameterValue(std::string("OPEN_LOOP")));
58  declare_parameter_if_not_declared(node, "scale_velocities", rclcpp::ParameterValue(false));
59  node->get_parameter("smoothing_frequency", smoothing_frequency_);
60  node->get_parameter("feedback", feedback_type);
61  node->get_parameter("scale_velocities", scale_velocities_);
62 
63  // Kinematics
64  declare_parameter_if_not_declared(
65  node, "max_velocity", rclcpp::ParameterValue(std::vector<double>{0.50, 0.0, 2.5}));
66  declare_parameter_if_not_declared(
67  node, "min_velocity", rclcpp::ParameterValue(std::vector<double>{-0.50, 0.0, -2.5}));
68  declare_parameter_if_not_declared(
69  node, "max_accel", rclcpp::ParameterValue(std::vector<double>{2.5, 0.0, 3.2}));
70  declare_parameter_if_not_declared(
71  node, "max_decel", rclcpp::ParameterValue(std::vector<double>{-2.5, 0.0, -3.2}));
72  node->get_parameter("max_velocity", max_velocities_);
73  node->get_parameter("min_velocity", min_velocities_);
74  node->get_parameter("max_accel", max_accels_);
75  node->get_parameter("max_decel", max_decels_);
76 
77  for (unsigned int i = 0; i != 3; i++) {
78  if (max_decels_[i] > 0.0) {
79  throw std::runtime_error(
80  "Positive values set of deceleration! These should be negative to slow down!");
81  }
82  if (max_accels_[i] < 0.0) {
83  throw std::runtime_error(
84  "Negative values set of acceleration! These should be positive to speed up!");
85  }
86  if (min_velocities_[i] > max_velocities_[i]) {
87  throw std::runtime_error(
88  "Min velocities are higher than max velocities!");
89  }
90  }
91 
92  // Get feature parameters
93  declare_parameter_if_not_declared(node, "odom_topic", rclcpp::ParameterValue("odom"));
94  declare_parameter_if_not_declared(node, "odom_duration", rclcpp::ParameterValue(0.1));
95  declare_parameter_if_not_declared(
96  node, "deadband_velocity", rclcpp::ParameterValue(std::vector<double>{0.0, 0.0, 0.0}));
97  declare_parameter_if_not_declared(node, "velocity_timeout", rclcpp::ParameterValue(1.0));
98  node->get_parameter("odom_topic", odom_topic_);
99  node->get_parameter("odom_duration", odom_duration_);
100  node->get_parameter("deadband_velocity", deadband_velocities_);
101  node->get_parameter("velocity_timeout", velocity_timeout_dbl);
102  velocity_timeout_ = rclcpp::Duration::from_seconds(velocity_timeout_dbl);
103 
104  if (max_velocities_.size() != 3 || min_velocities_.size() != 3 ||
105  max_accels_.size() != 3 || max_decels_.size() != 3 || deadband_velocities_.size() != 3)
106  {
107  throw std::runtime_error(
108  "Invalid setting of kinematic and/or deadband limits!"
109  " All limits must be size of 3 representing (x, y, theta).");
110  }
111 
112  // Get control type
113  if (feedback_type == "OPEN_LOOP") {
114  open_loop_ = true;
115  } else if (feedback_type == "CLOSED_LOOP") {
116  open_loop_ = false;
117  odom_smoother_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration_, odom_topic_);
118  } else {
119  throw std::runtime_error("Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
120  }
121 
122  // Setup inputs / outputs
123  smoothed_cmd_pub_ = create_publisher<geometry_msgs::msg::Twist>("cmd_vel_smoothed", 1);
124  cmd_sub_ = create_subscription<geometry_msgs::msg::Twist>(
125  "cmd_vel", rclcpp::QoS(1),
126  std::bind(&VelocitySmoother::inputCommandCallback, this, std::placeholders::_1));
127 
128  return nav2_util::CallbackReturn::SUCCESS;
129 }
130 
131 nav2_util::CallbackReturn
132 VelocitySmoother::on_activate(const rclcpp_lifecycle::State &)
133 {
134  RCLCPP_INFO(get_logger(), "Activating");
135  smoothed_cmd_pub_->on_activate();
136  double timer_duration_ms = 1000.0 / smoothing_frequency_;
137  timer_ = this->create_wall_timer(
138  std::chrono::milliseconds(static_cast<int>(timer_duration_ms)),
139  std::bind(&VelocitySmoother::smootherTimer, this));
140 
141  dyn_params_handler_ = this->add_on_set_parameters_callback(
142  std::bind(&VelocitySmoother::dynamicParametersCallback, this, _1));
143 
144  // create bond connection
145  createBond();
146  return nav2_util::CallbackReturn::SUCCESS;
147 }
148 
149 nav2_util::CallbackReturn
150 VelocitySmoother::on_deactivate(const rclcpp_lifecycle::State &)
151 {
152  RCLCPP_INFO(get_logger(), "Deactivating");
153  if (timer_) {
154  timer_->cancel();
155  timer_.reset();
156  }
157  smoothed_cmd_pub_->on_deactivate();
158  dyn_params_handler_.reset();
159 
160  // destroy bond connection
161  destroyBond();
162  return nav2_util::CallbackReturn::SUCCESS;
163 }
164 
165 nav2_util::CallbackReturn
166 VelocitySmoother::on_cleanup(const rclcpp_lifecycle::State &)
167 {
168  RCLCPP_INFO(get_logger(), "Cleaning up");
169  smoothed_cmd_pub_.reset();
170  odom_smoother_.reset();
171  cmd_sub_.reset();
172  return nav2_util::CallbackReturn::SUCCESS;
173 }
174 
175 nav2_util::CallbackReturn
176 VelocitySmoother::on_shutdown(const rclcpp_lifecycle::State &)
177 {
178  RCLCPP_INFO(get_logger(), "Shutting down");
179  return nav2_util::CallbackReturn::SUCCESS;
180 }
181 
182 void VelocitySmoother::inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg)
183 {
184  // If message contains NaN or Inf, ignore
185  if (!nav2_util::validateTwist(*msg)) {
186  RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
187  return;
188  }
189 
190  command_ = msg;
191  last_command_time_ = now();
192 }
193 
195  const double v_curr, const double v_cmd, const double accel, const double decel)
196 {
197  // Exploiting vector scaling properties
198  double dv = v_cmd - v_curr;
199 
200  double v_component_max;
201  double v_component_min;
202 
203  // Accelerating if magnitude of v_cmd is above magnitude of v_curr
204  // and if v_cmd and v_curr have the same sign (i.e. speed is NOT passing through 0.0)
205  // Decelerating otherwise
206  if (abs(v_cmd) >= abs(v_curr) && v_curr * v_cmd >= 0.0) {
207  v_component_max = accel / smoothing_frequency_;
208  v_component_min = -accel / smoothing_frequency_;
209  } else {
210  v_component_max = -decel / smoothing_frequency_;
211  v_component_min = decel / smoothing_frequency_;
212  }
213 
214  if (dv > v_component_max) {
215  return v_component_max / dv;
216  }
217 
218  if (dv < v_component_min) {
219  return v_component_min / dv;
220  }
221 
222  return -1.0;
223 }
224 
226  const double v_curr, const double v_cmd,
227  const double accel, const double decel, const double eta)
228 {
229  double dv = v_cmd - v_curr;
230 
231  double v_component_max;
232  double v_component_min;
233 
234  // Accelerating if magnitude of v_cmd is above magnitude of v_curr
235  // and if v_cmd and v_curr have the same sign (i.e. speed is NOT passing through 0.0)
236  // Decelerating otherwise
237  if (abs(v_cmd) >= abs(v_curr) && v_curr * v_cmd >= 0.0) {
238  v_component_max = accel / smoothing_frequency_;
239  v_component_min = -accel / smoothing_frequency_;
240  } else {
241  v_component_max = -decel / smoothing_frequency_;
242  v_component_min = decel / smoothing_frequency_;
243  }
244 
245  return v_curr + std::clamp(eta * dv, v_component_min, v_component_max);
246 }
247 
249 {
250  // Wait until the first command is received
251  if (!command_) {
252  return;
253  }
254 
255  auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>();
256 
257  // Check for velocity timeout. If nothing received, publish zeros to apply deceleration
258  if (now() - last_command_time_ > velocity_timeout_) {
259  if (last_cmd_ == geometry_msgs::msg::Twist() || stopped_) {
260  stopped_ = true;
261  return;
262  }
263  *command_ = geometry_msgs::msg::Twist();
264  }
265 
266  stopped_ = false;
267 
268  // Get current velocity based on feedback type
269  geometry_msgs::msg::Twist current_;
270  if (open_loop_) {
271  current_ = last_cmd_;
272  } else {
273  current_ = odom_smoother_->getTwist();
274  }
275 
276  // Apply absolute velocity restrictions to the command
277  command_->linear.x = std::clamp(command_->linear.x, min_velocities_[0], max_velocities_[0]);
278  command_->linear.y = std::clamp(command_->linear.y, min_velocities_[1], max_velocities_[1]);
279  command_->angular.z = std::clamp(command_->angular.z, min_velocities_[2], max_velocities_[2]);
280 
281  // Find if any component is not within the acceleration constraints. If so, store the most
282  // significant scale factor to apply to the vector <dvx, dvy, dvw>, eta, to reduce all axes
283  // proportionally to follow the same direction, within change of velocity bounds.
284  // In case eta reduces another axis out of its own limit, apply accel constraint to guarantee
285  // output is within limits, even if it deviates from requested command slightly.
286  double eta = 1.0;
287  if (scale_velocities_) {
288  double curr_eta = -1.0;
289 
290  curr_eta = findEtaConstraint(
291  current_.linear.x, command_->linear.x, max_accels_[0], max_decels_[0]);
292  if (curr_eta > 0.0 && std::fabs(1.0 - curr_eta) > std::fabs(1.0 - eta)) {
293  eta = curr_eta;
294  }
295 
296  curr_eta = findEtaConstraint(
297  current_.linear.y, command_->linear.y, max_accels_[1], max_decels_[1]);
298  if (curr_eta > 0.0 && std::fabs(1.0 - curr_eta) > std::fabs(1.0 - eta)) {
299  eta = curr_eta;
300  }
301 
302  curr_eta = findEtaConstraint(
303  current_.angular.z, command_->angular.z, max_accels_[2], max_decels_[2]);
304  if (curr_eta > 0.0 && std::fabs(1.0 - curr_eta) > std::fabs(1.0 - eta)) {
305  eta = curr_eta;
306  }
307  }
308 
309  cmd_vel->linear.x = applyConstraints(
310  current_.linear.x, command_->linear.x, max_accels_[0], max_decels_[0], eta);
311  cmd_vel->linear.y = applyConstraints(
312  current_.linear.y, command_->linear.y, max_accels_[1], max_decels_[1], eta);
313  cmd_vel->angular.z = applyConstraints(
314  current_.angular.z, command_->angular.z, max_accels_[2], max_decels_[2], eta);
315  last_cmd_ = *cmd_vel;
316 
317  // Apply deadband restrictions & publish
318  cmd_vel->linear.x = fabs(cmd_vel->linear.x) < deadband_velocities_[0] ? 0.0 : cmd_vel->linear.x;
319  cmd_vel->linear.y = fabs(cmd_vel->linear.y) < deadband_velocities_[1] ? 0.0 : cmd_vel->linear.y;
320  cmd_vel->angular.z = fabs(cmd_vel->angular.z) <
321  deadband_velocities_[2] ? 0.0 : cmd_vel->angular.z;
322 
323  smoothed_cmd_pub_->publish(std::move(cmd_vel));
324 }
325 
326 rcl_interfaces::msg::SetParametersResult
327 VelocitySmoother::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
328 {
329  rcl_interfaces::msg::SetParametersResult result;
330  result.successful = true;
331 
332  for (auto parameter : parameters) {
333  const auto & type = parameter.get_type();
334  const auto & name = parameter.get_name();
335 
336  if (type == ParameterType::PARAMETER_DOUBLE) {
337  if (name == "smoothing_frequency") {
338  smoothing_frequency_ = parameter.as_double();
339  if (timer_) {
340  timer_->cancel();
341  timer_.reset();
342  }
343 
344  double timer_duration_ms = 1000.0 / smoothing_frequency_;
345  timer_ = this->create_wall_timer(
346  std::chrono::milliseconds(static_cast<int>(timer_duration_ms)),
347  std::bind(&VelocitySmoother::smootherTimer, this));
348  } else if (name == "velocity_timeout") {
349  velocity_timeout_ = rclcpp::Duration::from_seconds(parameter.as_double());
350  } else if (name == "odom_duration") {
351  odom_duration_ = parameter.as_double();
352  odom_smoother_ =
353  std::make_unique<nav2_util::OdomSmoother>(
354  shared_from_this(), odom_duration_, odom_topic_);
355  }
356  } else if (type == ParameterType::PARAMETER_DOUBLE_ARRAY) {
357  if (parameter.as_double_array().size() != 3) {
358  RCLCPP_WARN(get_logger(), "Invalid size of parameter %s. Must be size 3", name.c_str());
359  result.successful = false;
360  break;
361  }
362 
363  if (name == "max_velocity") {
364  max_velocities_ = parameter.as_double_array();
365  } else if (name == "min_velocity") {
366  min_velocities_ = parameter.as_double_array();
367  } else if (name == "max_accel") {
368  for (unsigned int i = 0; i != 3; i++) {
369  if (parameter.as_double_array()[i] < 0.0) {
370  RCLCPP_WARN(
371  get_logger(),
372  "Negative values set of acceleration! These should be positive to speed up!");
373  result.successful = false;
374  }
375  }
376  max_accels_ = parameter.as_double_array();
377  } else if (name == "max_decel") {
378  for (unsigned int i = 0; i != 3; i++) {
379  if (parameter.as_double_array()[i] > 0.0) {
380  RCLCPP_WARN(
381  get_logger(),
382  "Positive values set of deceleration! These should be negative to slow down!");
383  result.successful = false;
384  }
385  }
386  max_decels_ = parameter.as_double_array();
387  } else if (name == "deadband_velocity") {
388  deadband_velocities_ = parameter.as_double_array();
389  }
390  } else if (type == ParameterType::PARAMETER_STRING) {
391  if (name == "feedback") {
392  if (parameter.as_string() == "OPEN_LOOP") {
393  open_loop_ = true;
394  odom_smoother_.reset();
395  } else if (parameter.as_string() == "CLOSED_LOOP") {
396  open_loop_ = false;
397  odom_smoother_ =
398  std::make_unique<nav2_util::OdomSmoother>(
399  shared_from_this(), odom_duration_, odom_topic_);
400  } else {
401  RCLCPP_WARN(
402  get_logger(), "Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
403  result.successful = false;
404  break;
405  }
406  } else if (name == "odom_topic") {
407  odom_topic_ = parameter.as_string();
408  odom_smoother_ =
409  std::make_unique<nav2_util::OdomSmoother>(
410  shared_from_this(), odom_duration_, odom_topic_);
411  }
412  }
413  }
414 
415  return result;
416 }
417 
418 } // namespace nav2_velocity_smoother
419 
420 #include "rclcpp_components/register_node_macro.hpp"
421 RCLCPP_COMPONENTS_REGISTER_NODE(nav2_velocity_smoother::VelocitySmoother)
std::shared_ptr< nav2_util::LifecycleNode > shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
void destroyBond()
Destroy bond connection to lifecycle manager.
This class that smooths cmd_vel velocities for robot bases.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates member variables.
~VelocitySmoother()
Destructor for nav2_velocity_smoother::VelocitySmoother.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Configures parameters and member variables.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Calls clean up states and resets member variables.
void inputCommandCallback(const geometry_msgs::msg::Twist::SharedPtr msg)
Callback for incoming velocity commands.
double findEtaConstraint(const double v_curr, const double v_cmd, const double accel, const double decel)
Find the scale factor, eta, which scales axis into acceleration range.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Dynamic reconfigure callback.
void smootherTimer()
Main worker timer function.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Activates member variables.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
double applyConstraints(const double v_curr, const double v_cmd, const double accel, const double decel, const double eta)
Apply acceleration and scale factor constraints.