Nav2 Navigation Stack - kilted  kilted
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 & 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  RCLCPP_ERROR(
80  get_logger(),
81  "Positive values set of deceleration! These should be negative to slow down!");
82  on_cleanup(state);
83  return nav2_util::CallbackReturn::FAILURE;
84  }
85  if (max_accels_[i] < 0.0) {
86  RCLCPP_ERROR(
87  get_logger(),
88  "Negative values set of acceleration! These should be positive to speed up!");
89  on_cleanup(state);
90  return nav2_util::CallbackReturn::FAILURE;
91  }
92  if (min_velocities_[i] > 0.0) {
93  RCLCPP_ERROR(
94  get_logger(), "Positive values set of min_velocities! These should be negative!");
95  on_cleanup(state);
96  return nav2_util::CallbackReturn::FAILURE;
97  }
98  if (max_velocities_[i] < 0.0) {
99  RCLCPP_ERROR(
100  get_logger(), "Negative values set of max_velocities! These should be positive!");
101  on_cleanup(state);
102  return nav2_util::CallbackReturn::FAILURE;
103  }
104  if (min_velocities_[i] > max_velocities_[i]) {
105  RCLCPP_ERROR(get_logger(), "Min velocities are higher than max velocities!");
106  on_cleanup(state);
107  return nav2_util::CallbackReturn::FAILURE;
108  }
109  }
110 
111  // Get feature parameters
112  declare_parameter_if_not_declared(node, "odom_topic", rclcpp::ParameterValue("odom"));
113  declare_parameter_if_not_declared(node, "odom_duration", rclcpp::ParameterValue(0.1));
114  declare_parameter_if_not_declared(
115  node, "deadband_velocity", rclcpp::ParameterValue(std::vector<double>{0.0, 0.0, 0.0}));
116  declare_parameter_if_not_declared(node, "velocity_timeout", rclcpp::ParameterValue(1.0));
117  node->get_parameter("odom_topic", odom_topic_);
118  node->get_parameter("odom_duration", odom_duration_);
119  node->get_parameter("deadband_velocity", deadband_velocities_);
120  node->get_parameter("velocity_timeout", velocity_timeout_dbl);
121  velocity_timeout_ = rclcpp::Duration::from_seconds(velocity_timeout_dbl);
122 
123  if (max_velocities_.size() != 3 || min_velocities_.size() != 3 ||
124  max_accels_.size() != 3 || max_decels_.size() != 3 || deadband_velocities_.size() != 3)
125  {
126  RCLCPP_ERROR(
127  get_logger(),
128  "Invalid setting of kinematic and/or deadband limits!"
129  " All limits must be size of 3 representing (x, y, theta).");
130  on_cleanup(state);
131  return nav2_util::CallbackReturn::FAILURE;
132  }
133 
134  // Get control type
135  if (feedback_type == "OPEN_LOOP") {
136  open_loop_ = true;
137  } else if (feedback_type == "CLOSED_LOOP") {
138  open_loop_ = false;
139  odom_smoother_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration_, odom_topic_);
140  } else {
141  RCLCPP_ERROR(
142  get_logger(),
143  "Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
144  on_cleanup(state);
145  return nav2_util::CallbackReturn::FAILURE;
146  }
147 
148  // Setup inputs / outputs
149  smoothed_cmd_pub_ = std::make_unique<nav2_util::TwistPublisher>(node, "cmd_vel_smoothed", 1);
150  cmd_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
151  node,
152  "cmd_vel", rclcpp::QoS(1),
153  std::bind(&VelocitySmoother::inputCommandCallback, this, std::placeholders::_1),
154  std::bind(&VelocitySmoother::inputCommandStampedCallback, this, std::placeholders::_1)
155  );
156 
157  declare_parameter_if_not_declared(node, "use_realtime_priority", rclcpp::ParameterValue(false));
158  bool use_realtime_priority = false;
159  node->get_parameter("use_realtime_priority", use_realtime_priority);
160  if (use_realtime_priority) {
161  try {
162  nav2_util::setSoftRealTimePriority();
163  } catch (const std::runtime_error & e) {
164  RCLCPP_ERROR(get_logger(), "%s", e.what());
165  on_cleanup(state);
166  return nav2_util::CallbackReturn::FAILURE;
167  }
168  }
169 
170  return nav2_util::CallbackReturn::SUCCESS;
171 }
172 
173 nav2_util::CallbackReturn
174 VelocitySmoother::on_activate(const rclcpp_lifecycle::State &)
175 {
176  RCLCPP_INFO(get_logger(), "Activating");
177  smoothed_cmd_pub_->on_activate();
178  double timer_duration_ms = 1000.0 / smoothing_frequency_;
179  timer_ = this->create_wall_timer(
180  std::chrono::milliseconds(static_cast<int>(timer_duration_ms)),
181  std::bind(&VelocitySmoother::smootherTimer, this));
182 
183  dyn_params_handler_ = this->add_on_set_parameters_callback(
184  std::bind(&VelocitySmoother::dynamicParametersCallback, this, _1));
185 
186  // create bond connection
187  createBond();
188  return nav2_util::CallbackReturn::SUCCESS;
189 }
190 
191 nav2_util::CallbackReturn
192 VelocitySmoother::on_deactivate(const rclcpp_lifecycle::State &)
193 {
194  RCLCPP_INFO(get_logger(), "Deactivating");
195  if (timer_) {
196  timer_->cancel();
197  timer_.reset();
198  }
199  smoothed_cmd_pub_->on_deactivate();
200 
201  remove_on_set_parameters_callback(dyn_params_handler_.get());
202  dyn_params_handler_.reset();
203 
204  // destroy bond connection
205  destroyBond();
206  return nav2_util::CallbackReturn::SUCCESS;
207 }
208 
209 nav2_util::CallbackReturn
210 VelocitySmoother::on_cleanup(const rclcpp_lifecycle::State &)
211 {
212  RCLCPP_INFO(get_logger(), "Cleaning up");
213  smoothed_cmd_pub_.reset();
214  odom_smoother_.reset();
215  cmd_sub_.reset();
216  return nav2_util::CallbackReturn::SUCCESS;
217 }
218 
219 nav2_util::CallbackReturn
220 VelocitySmoother::on_shutdown(const rclcpp_lifecycle::State &)
221 {
222  RCLCPP_INFO(get_logger(), "Shutting down");
223  return nav2_util::CallbackReturn::SUCCESS;
224 }
225 
226 void VelocitySmoother::inputCommandStampedCallback(
227  const geometry_msgs::msg::TwistStamped::SharedPtr msg)
228 {
229  // If message contains NaN or Inf, ignore
230  if (!nav2_util::validateTwist(msg->twist)) {
231  RCLCPP_ERROR(get_logger(), "Velocity message contains NaNs or Infs! Ignoring as invalid!");
232  return;
233  }
234 
235  command_ = msg;
236  if (msg->header.stamp.sec == 0 && msg->header.stamp.nanosec == 0) {
237  last_command_time_ = now();
238  } else {
239  last_command_time_ = msg->header.stamp;
240  }
241 }
242 
244  geometry_msgs::msg::Twist::SharedPtr msg)
245 {
246  auto twist_stamped = std::make_shared<geometry_msgs::msg::TwistStamped>();
247  twist_stamped->twist = *msg;
248  inputCommandStampedCallback(twist_stamped);
249 }
250 
252  const double v_curr, const double v_cmd, const double accel, const double decel)
253 {
254  // Exploiting vector scaling properties
255  double dv = v_cmd - v_curr;
256 
257  double v_component_max;
258  double v_component_min;
259 
260  // Accelerating if magnitude of v_cmd is above magnitude of v_curr
261  // and if v_cmd and v_curr have the same sign (i.e. speed is NOT passing through 0.0)
262  // Decelerating otherwise
263  if (abs(v_cmd) >= abs(v_curr) && v_curr * v_cmd >= 0.0) {
264  v_component_max = accel / smoothing_frequency_;
265  v_component_min = -accel / smoothing_frequency_;
266  } else {
267  v_component_max = -decel / smoothing_frequency_;
268  v_component_min = decel / smoothing_frequency_;
269  }
270 
271  if (dv > v_component_max) {
272  return v_component_max / dv;
273  }
274 
275  if (dv < v_component_min) {
276  return v_component_min / dv;
277  }
278 
279  return -1.0;
280 }
281 
283  const double v_curr, const double v_cmd,
284  const double accel, const double decel, const double eta)
285 {
286  double dv = v_cmd - v_curr;
287 
288  double v_component_max;
289  double v_component_min;
290 
291  // Accelerating if magnitude of v_cmd is above magnitude of v_curr
292  // and if v_cmd and v_curr have the same sign (i.e. speed is NOT passing through 0.0)
293  // Decelerating otherwise
294  if (abs(v_cmd) >= abs(v_curr) && v_curr * v_cmd >= 0.0) {
295  v_component_max = accel / smoothing_frequency_;
296  v_component_min = -accel / smoothing_frequency_;
297  } else {
298  v_component_max = -decel / smoothing_frequency_;
299  v_component_min = decel / smoothing_frequency_;
300  }
301 
302  return v_curr + std::clamp(eta * dv, v_component_min, v_component_max);
303 }
304 
306 {
307  // Wait until the first command is received
308  if (!command_) {
309  return;
310  }
311 
312  auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
313  cmd_vel->header = command_->header;
314 
315  // Check for velocity timeout. If nothing received, publish zeros to apply deceleration
316  if (now() - last_command_time_ > velocity_timeout_) {
317  if (last_cmd_.twist == geometry_msgs::msg::Twist() || stopped_) {
318  stopped_ = true;
319  return;
320  }
321  *command_ = geometry_msgs::msg::TwistStamped();
322  command_->header.stamp = now();
323  }
324 
325  stopped_ = false;
326 
327  // Get current velocity based on feedback type
328  geometry_msgs::msg::TwistStamped current_;
329  if (open_loop_) {
330  current_ = last_cmd_;
331  } else {
332  current_ = odom_smoother_->getTwistStamped();
333  }
334 
335  // Apply absolute velocity restrictions to the command
336  command_->twist.linear.x = std::clamp(
337  command_->twist.linear.x, min_velocities_[0],
338  max_velocities_[0]);
339  command_->twist.linear.y = std::clamp(
340  command_->twist.linear.y, min_velocities_[1],
341  max_velocities_[1]);
342  command_->twist.angular.z = std::clamp(
343  command_->twist.angular.z, min_velocities_[2],
344  max_velocities_[2]);
345 
346  // Find if any component is not within the acceleration constraints. If so, store the most
347  // significant scale factor to apply to the vector <dvx, dvy, dvw>, eta, to reduce all axes
348  // proportionally to follow the same direction, within change of velocity bounds.
349  // In case eta reduces another axis out of its own limit, apply accel constraint to guarantee
350  // output is within limits, even if it deviates from requested command slightly.
351  double eta = 1.0;
352  if (scale_velocities_) {
353  double curr_eta = -1.0;
354 
355  curr_eta = findEtaConstraint(
356  current_.twist.linear.x, command_->twist.linear.x, max_accels_[0], max_decels_[0]);
357  if (curr_eta > 0.0 && std::fabs(1.0 - curr_eta) > std::fabs(1.0 - eta)) {
358  eta = curr_eta;
359  }
360 
361  curr_eta = findEtaConstraint(
362  current_.twist.linear.y, command_->twist.linear.y, max_accels_[1], max_decels_[1]);
363  if (curr_eta > 0.0 && std::fabs(1.0 - curr_eta) > std::fabs(1.0 - eta)) {
364  eta = curr_eta;
365  }
366 
367  curr_eta = findEtaConstraint(
368  current_.twist.angular.z, command_->twist.angular.z, max_accels_[2], max_decels_[2]);
369  if (curr_eta > 0.0 && std::fabs(1.0 - curr_eta) > std::fabs(1.0 - eta)) {
370  eta = curr_eta;
371  }
372  }
373 
374  cmd_vel->twist.linear.x = applyConstraints(
375  current_.twist.linear.x, command_->twist.linear.x, max_accels_[0], max_decels_[0], eta);
376  cmd_vel->twist.linear.y = applyConstraints(
377  current_.twist.linear.y, command_->twist.linear.y, max_accels_[1], max_decels_[1], eta);
378  cmd_vel->twist.angular.z = applyConstraints(
379  current_.twist.angular.z, command_->twist.angular.z, max_accels_[2], max_decels_[2], eta);
380  last_cmd_ = *cmd_vel;
381 
382  // Apply deadband restrictions & publish
383  cmd_vel->twist.linear.x =
384  fabs(cmd_vel->twist.linear.x) < deadband_velocities_[0] ? 0.0 : cmd_vel->twist.linear.x;
385  cmd_vel->twist.linear.y =
386  fabs(cmd_vel->twist.linear.y) < deadband_velocities_[1] ? 0.0 : cmd_vel->twist.linear.y;
387  cmd_vel->twist.angular.z =
388  fabs(cmd_vel->twist.angular.z) < deadband_velocities_[2] ? 0.0 : cmd_vel->twist.angular.z;
389 
390  smoothed_cmd_pub_->publish(std::move(cmd_vel));
391 }
392 
393 rcl_interfaces::msg::SetParametersResult
394 VelocitySmoother::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
395 {
396  rcl_interfaces::msg::SetParametersResult result;
397  result.successful = true;
398 
399  for (auto parameter : parameters) {
400  const auto & param_type = parameter.get_type();
401  const auto & param_name = parameter.get_name();
402  if (param_name.find('.') != std::string::npos) {
403  continue;
404  }
405 
406  if (param_type == ParameterType::PARAMETER_DOUBLE) {
407  if (param_name == "smoothing_frequency") {
408  smoothing_frequency_ = parameter.as_double();
409  if (timer_) {
410  timer_->cancel();
411  timer_.reset();
412  }
413 
414  double timer_duration_ms = 1000.0 / smoothing_frequency_;
415  timer_ = this->create_wall_timer(
416  std::chrono::milliseconds(static_cast<int>(timer_duration_ms)),
417  std::bind(&VelocitySmoother::smootherTimer, this));
418  } else if (param_name == "velocity_timeout") {
419  velocity_timeout_ = rclcpp::Duration::from_seconds(parameter.as_double());
420  } else if (param_name == "odom_duration") {
421  odom_duration_ = parameter.as_double();
422  odom_smoother_ =
423  std::make_unique<nav2_util::OdomSmoother>(
424  shared_from_this(), odom_duration_, odom_topic_);
425  }
426  } else if (param_type == ParameterType::PARAMETER_DOUBLE_ARRAY) {
427  if (parameter.as_double_array().size() != 3) {
428  RCLCPP_WARN(get_logger(), "Invalid size of parameter %s. Must be size 3",
429  param_name.c_str());
430  result.successful = false;
431  break;
432  }
433 
434  if (param_name == "max_velocity") {
435  for (unsigned int i = 0; i != 3; i++) {
436  if (parameter.as_double_array()[i] < 0.0) {
437  RCLCPP_WARN(
438  get_logger(),
439  "Negative values set of max_velocity! These should be positive!");
440  result.successful = false;
441  }
442  }
443  if (result.successful) {
444  max_velocities_ = parameter.as_double_array();
445  }
446  } else if (param_name == "min_velocity") {
447  for (unsigned int i = 0; i != 3; i++) {
448  if (parameter.as_double_array()[i] > 0.0) {
449  RCLCPP_WARN(
450  get_logger(),
451  "Positive values set of min_velocity! These should be negative!");
452  result.successful = false;
453  }
454  }
455  if (result.successful) {
456  min_velocities_ = parameter.as_double_array();
457  }
458  } else if (param_name == "max_accel") {
459  for (unsigned int i = 0; i != 3; i++) {
460  if (parameter.as_double_array()[i] < 0.0) {
461  RCLCPP_WARN(
462  get_logger(),
463  "Negative values set of acceleration! These should be positive to speed up!");
464  result.successful = false;
465  }
466  }
467  if (result.successful) {
468  max_accels_ = parameter.as_double_array();
469  }
470  } else if (param_name == "max_decel") {
471  for (unsigned int i = 0; i != 3; i++) {
472  if (parameter.as_double_array()[i] > 0.0) {
473  RCLCPP_WARN(
474  get_logger(),
475  "Positive values set of deceleration! These should be negative to slow down!");
476  result.successful = false;
477  }
478  }
479  if (result.successful) {
480  max_decels_ = parameter.as_double_array();
481  }
482  } else if (param_name == "deadband_velocity") {
483  deadband_velocities_ = parameter.as_double_array();
484  }
485  } else if (param_type == ParameterType::PARAMETER_STRING) {
486  if (param_name == "feedback") {
487  if (parameter.as_string() == "OPEN_LOOP") {
488  open_loop_ = true;
489  odom_smoother_.reset();
490  } else if (parameter.as_string() == "CLOSED_LOOP") {
491  open_loop_ = false;
492  odom_smoother_ =
493  std::make_unique<nav2_util::OdomSmoother>(
494  shared_from_this(), odom_duration_, odom_topic_);
495  } else {
496  RCLCPP_WARN(
497  get_logger(), "Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
498  result.successful = false;
499  break;
500  }
501  } else if (param_name == "odom_topic") {
502  odom_topic_ = parameter.as_string();
503  odom_smoother_ =
504  std::make_unique<nav2_util::OdomSmoother>(
505  shared_from_this(), odom_duration_, odom_topic_);
506  }
507  }
508  }
509 
510  return result;
511 }
512 
513 } // namespace nav2_velocity_smoother
514 
515 #include "rclcpp_components/register_node_macro.hpp"
516 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.