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