22 #include "nav2_velocity_smoother/velocity_smoother.hpp"
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;
29 namespace nav2_velocity_smoother
32 VelocitySmoother::VelocitySmoother(
const rclcpp::NodeOptions & options)
33 : LifecycleNode(
"velocity_smoother",
"", options),
34 last_command_time_{0, 0, get_clock()->get_clock_type()}
49 RCLCPP_INFO(get_logger(),
"Configuring velocity smoother");
51 std::string feedback_type;
52 double velocity_timeout_dbl;
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_);
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_);
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);
90 size_t size = max_velocities_.size();
91 is_6dof_ = (size == 6);
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)
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)");
104 return nav2::CallbackReturn::FAILURE;
107 for (
unsigned int i = 0; i != size; i++) {
108 if (max_decels_[i] > 0.0) {
111 "Positive values set of deceleration! These should be negative to slow down!");
113 return nav2::CallbackReturn::FAILURE;
115 if (max_accels_[i] < 0.0) {
118 "Negative values set of acceleration! These should be positive to speed up!");
120 return nav2::CallbackReturn::FAILURE;
122 if (min_velocities_[i] > 0.0) {
124 get_logger(),
"Positive values set of min_velocities! These should be negative!");
126 return nav2::CallbackReturn::FAILURE;
128 if (max_velocities_[i] < 0.0) {
130 get_logger(),
"Negative values set of max_velocities! These should be positive!");
132 return nav2::CallbackReturn::FAILURE;
134 if (min_velocities_[i] > max_velocities_[i]) {
135 RCLCPP_ERROR(get_logger(),
"Min velocities are higher than max velocities!");
137 return nav2::CallbackReturn::FAILURE;
142 if (feedback_type ==
"OPEN_LOOP") {
144 }
else if (feedback_type ==
"CLOSED_LOOP") {
146 odom_smoother_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration_, odom_topic_);
150 "Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
152 return nav2::CallbackReturn::FAILURE;
156 smoothed_cmd_pub_ = std::make_unique<nav2_util::TwistPublisher>(node,
"cmd_vel_smoothed");
157 cmd_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
161 std::bind(&VelocitySmoother::inputCommandStampedCallback,
this, std::placeholders::_1));
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) {
168 nav2::setSoftRealTimePriority();
169 }
catch (
const std::runtime_error & e) {
170 RCLCPP_ERROR(get_logger(),
"%s", e.what());
172 return nav2::CallbackReturn::FAILURE;
176 return nav2::CallbackReturn::SUCCESS;
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)),
189 dyn_params_handler_ = this->add_on_set_parameters_callback(
194 return nav2::CallbackReturn::SUCCESS;
200 RCLCPP_INFO(get_logger(),
"Deactivating");
205 smoothed_cmd_pub_->on_deactivate();
207 remove_on_set_parameters_callback(dyn_params_handler_.get());
208 dyn_params_handler_.reset();
212 return nav2::CallbackReturn::SUCCESS;
218 RCLCPP_INFO(get_logger(),
"Cleaning up");
219 smoothed_cmd_pub_.reset();
220 odom_smoother_.reset();
222 return nav2::CallbackReturn::SUCCESS;
228 RCLCPP_INFO(get_logger(),
"Shutting down");
229 return nav2::CallbackReturn::SUCCESS;
232 void VelocitySmoother::inputCommandStampedCallback(
233 const geometry_msgs::msg::TwistStamped::SharedPtr msg)
236 if (!nav2_util::validateTwist(msg->twist)) {
237 RCLCPP_ERROR(get_logger(),
"Velocity message contains NaNs or Infs! Ignoring as invalid!");
242 if (msg->header.stamp.sec == 0 && msg->header.stamp.nanosec == 0) {
243 last_command_time_ = now();
245 last_command_time_ = msg->header.stamp;
250 geometry_msgs::msg::Twist::SharedPtr msg)
252 auto twist_stamped = std::make_shared<geometry_msgs::msg::TwistStamped>();
253 twist_stamped->twist = *msg;
254 inputCommandStampedCallback(twist_stamped);
258 const double v_curr,
const double v_cmd,
const double accel,
const double decel)
261 double dv = v_cmd - v_curr;
263 double v_component_max;
264 double v_component_min;
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_;
273 v_component_max = -decel / smoothing_frequency_;
274 v_component_min = decel / smoothing_frequency_;
277 if (dv > v_component_max) {
278 return v_component_max / dv;
281 if (dv < v_component_min) {
282 return v_component_min / dv;
289 const double v_curr,
const double v_cmd,
290 const double accel,
const double decel,
const double eta)
292 double dv = v_cmd - v_curr;
294 double v_component_max;
295 double v_component_min;
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_;
304 v_component_max = -decel / smoothing_frequency_;
305 v_component_min = decel / smoothing_frequency_;
308 return v_curr + std::clamp(eta * dv, v_component_min, v_component_max);
318 auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
319 cmd_vel->header = command_->header;
322 if (now() - last_command_time_ > velocity_timeout_) {
323 if (last_cmd_.twist == geometry_msgs::msg::Twist() || stopped_) {
327 *command_ = geometry_msgs::msg::TwistStamped();
328 command_->header.stamp = now();
334 geometry_msgs::msg::TwistStamped current_;
336 current_ = last_cmd_;
338 current_ = odom_smoother_->getTwistStamped();
343 command_->twist.linear.x = std::clamp(
344 command_->twist.linear.x, min_velocities_[0],
346 command_->twist.linear.y = std::clamp(
347 command_->twist.linear.y, min_velocities_[1],
349 command_->twist.angular.z = std::clamp(
350 command_->twist.angular.z, min_velocities_[2],
353 command_->twist.linear.x = std::clamp(
354 command_->twist.linear.x, min_velocities_[0],
356 command_->twist.linear.y = std::clamp(
357 command_->twist.linear.y, min_velocities_[1],
359 command_->twist.linear.z = std::clamp(
360 command_->twist.linear.z, min_velocities_[2],
362 command_->twist.angular.x = std::clamp(
363 command_->twist.angular.x, min_velocities_[3],
365 command_->twist.angular.y = std::clamp(
366 command_->twist.angular.y, min_velocities_[4],
368 command_->twist.angular.z = std::clamp(
369 command_->twist.angular.z, min_velocities_[5],
379 if (scale_velocities_) {
380 double curr_eta = -1.0;
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)) {
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)) {
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)) {
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)) {
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)) {
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)) {
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)) {
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)) {
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)) {
440 current_.twist.linear.x, command_->twist.linear.x, max_accels_[0], max_decels_[0], eta);
442 current_.twist.linear.y, command_->twist.linear.y, max_accels_[1], max_decels_[1], eta);
444 current_.twist.angular.z, command_->twist.angular.z, max_accels_[2], max_decels_[2], eta);
447 current_.twist.linear.x, command_->twist.linear.x, max_accels_[0], max_decels_[0], eta);
449 current_.twist.linear.y, command_->twist.linear.y, max_accels_[1], max_decels_[1], eta);
451 current_.twist.linear.z, command_->twist.linear.z, max_accels_[2], max_decels_[2], eta);
453 current_.twist.angular.x, command_->twist.angular.x, max_accels_[3], max_decels_[3], eta);
455 current_.twist.angular.y, command_->twist.angular.y, max_accels_[4], max_decels_[4], eta);
457 current_.twist.angular.z, command_->twist.angular.z, max_accels_[5], max_decels_[5], eta);
460 last_cmd_ = *cmd_vel;
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;
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;
488 smoothed_cmd_pub_->publish(std::move(cmd_vel));
491 rcl_interfaces::msg::SetParametersResult
494 rcl_interfaces::msg::SetParametersResult result;
495 result.successful =
true;
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) {
504 if (param_type == ParameterType::PARAMETER_DOUBLE) {
505 if (param_name ==
"smoothing_frequency") {
506 smoothing_frequency_ = parameter.as_double();
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)),
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();
521 std::make_unique<nav2_util::OdomSmoother>(
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;
533 if (param_name ==
"max_velocity") {
534 for (
unsigned int i = 0; i != size; i++) {
535 if (parameter.as_double_array()[i] < 0.0) {
538 "Negative values set of max_velocity! These should be positive!");
539 result.successful =
false;
542 if (result.successful) {
543 max_velocities_ = parameter.as_double_array();
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) {
550 "Positive values set of min_velocity! These should be negative!");
551 result.successful =
false;
554 if (result.successful) {
555 min_velocities_ = parameter.as_double_array();
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) {
562 "Negative values set of acceleration! These should be positive to speed up!");
563 result.successful =
false;
566 if (result.successful) {
567 max_accels_ = parameter.as_double_array();
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) {
574 "Positive values set of deceleration! These should be negative to slow down!");
575 result.successful =
false;
578 if (result.successful) {
579 max_decels_ = parameter.as_double_array();
581 }
else if (param_name ==
"deadband_velocity") {
582 deadband_velocities_ = parameter.as_double_array();
584 }
else if (param_type == ParameterType::PARAMETER_STRING) {
585 if (param_name ==
"feedback") {
586 if (parameter.as_string() ==
"OPEN_LOOP") {
588 odom_smoother_.reset();
589 }
else if (parameter.as_string() ==
"CLOSED_LOOP") {
592 std::make_unique<nav2_util::OdomSmoother>(
596 get_logger(),
"Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
597 result.successful =
false;
600 }
else if (param_name ==
"odom_topic") {
601 odom_topic_ = parameter.as_string();
603 std::make_unique<nav2_util::OdomSmoother>(
614 #include "rclcpp_components/register_node_macro.hpp"
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.