22 #include "nav2_velocity_smoother/velocity_smoother.hpp"
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;
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()}
46 nav2_util::CallbackReturn
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_);
77 for (
unsigned int i = 0; i != 3; i++) {
78 if (max_decels_[i] > 0.0) {
81 "Positive values set of deceleration! These should be negative to slow down!");
83 return nav2_util::CallbackReturn::FAILURE;
85 if (max_accels_[i] < 0.0) {
88 "Negative values set of acceleration! These should be positive to speed up!");
90 return nav2_util::CallbackReturn::FAILURE;
92 if (min_velocities_[i] > 0.0) {
94 get_logger(),
"Positive values set of min_velocities! These should be negative!");
96 return nav2_util::CallbackReturn::FAILURE;
98 if (max_velocities_[i] < 0.0) {
100 get_logger(),
"Negative values set of max_velocities! These should be positive!");
102 return nav2_util::CallbackReturn::FAILURE;
104 if (min_velocities_[i] > max_velocities_[i]) {
105 RCLCPP_ERROR(get_logger(),
"Min velocities are higher than max velocities!");
107 return nav2_util::CallbackReturn::FAILURE;
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);
123 if (max_velocities_.size() != 3 || min_velocities_.size() != 3 ||
124 max_accels_.size() != 3 || max_decels_.size() != 3 || deadband_velocities_.size() != 3)
128 "Invalid setting of kinematic and/or deadband limits!"
129 " All limits must be size of 3 representing (x, y, theta).");
131 return nav2_util::CallbackReturn::FAILURE;
135 if (feedback_type ==
"OPEN_LOOP") {
137 }
else if (feedback_type ==
"CLOSED_LOOP") {
139 odom_smoother_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration_, odom_topic_);
143 "Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
145 return nav2_util::CallbackReturn::FAILURE;
149 smoothed_cmd_pub_ = std::make_unique<nav2_util::TwistPublisher>(node,
"cmd_vel_smoothed", 1);
150 cmd_sub_ = std::make_unique<nav2_util::TwistSubscriber>(
152 "cmd_vel", rclcpp::QoS(1),
154 std::bind(&VelocitySmoother::inputCommandStampedCallback,
this, std::placeholders::_1)
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) {
162 nav2_util::setSoftRealTimePriority();
163 }
catch (
const std::runtime_error & e) {
164 RCLCPP_ERROR(get_logger(),
"%s", e.what());
166 return nav2_util::CallbackReturn::FAILURE;
170 return nav2_util::CallbackReturn::SUCCESS;
173 nav2_util::CallbackReturn
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)),
183 dyn_params_handler_ = this->add_on_set_parameters_callback(
188 return nav2_util::CallbackReturn::SUCCESS;
191 nav2_util::CallbackReturn
194 RCLCPP_INFO(get_logger(),
"Deactivating");
199 smoothed_cmd_pub_->on_deactivate();
201 remove_on_set_parameters_callback(dyn_params_handler_.get());
202 dyn_params_handler_.reset();
206 return nav2_util::CallbackReturn::SUCCESS;
209 nav2_util::CallbackReturn
212 RCLCPP_INFO(get_logger(),
"Cleaning up");
213 smoothed_cmd_pub_.reset();
214 odom_smoother_.reset();
216 return nav2_util::CallbackReturn::SUCCESS;
219 nav2_util::CallbackReturn
222 RCLCPP_INFO(get_logger(),
"Shutting down");
223 return nav2_util::CallbackReturn::SUCCESS;
226 void VelocitySmoother::inputCommandStampedCallback(
227 const geometry_msgs::msg::TwistStamped::SharedPtr msg)
230 if (!nav2_util::validateTwist(msg->twist)) {
231 RCLCPP_ERROR(get_logger(),
"Velocity message contains NaNs or Infs! Ignoring as invalid!");
236 if (msg->header.stamp.sec == 0 && msg->header.stamp.nanosec == 0) {
237 last_command_time_ = now();
239 last_command_time_ = msg->header.stamp;
244 geometry_msgs::msg::Twist::SharedPtr msg)
246 auto twist_stamped = std::make_shared<geometry_msgs::msg::TwistStamped>();
247 twist_stamped->twist = *msg;
248 inputCommandStampedCallback(twist_stamped);
252 const double v_curr,
const double v_cmd,
const double accel,
const double decel)
255 double dv = v_cmd - v_curr;
257 double v_component_max;
258 double v_component_min;
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_;
267 v_component_max = -decel / smoothing_frequency_;
268 v_component_min = decel / smoothing_frequency_;
271 if (dv > v_component_max) {
272 return v_component_max / dv;
275 if (dv < v_component_min) {
276 return v_component_min / dv;
283 const double v_curr,
const double v_cmd,
284 const double accel,
const double decel,
const double eta)
286 double dv = v_cmd - v_curr;
288 double v_component_max;
289 double v_component_min;
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_;
298 v_component_max = -decel / smoothing_frequency_;
299 v_component_min = decel / smoothing_frequency_;
302 return v_curr + std::clamp(eta * dv, v_component_min, v_component_max);
312 auto cmd_vel = std::make_unique<geometry_msgs::msg::TwistStamped>();
313 cmd_vel->header = command_->header;
316 if (now() - last_command_time_ > velocity_timeout_) {
317 if (last_cmd_.twist == geometry_msgs::msg::Twist() || stopped_) {
321 *command_ = geometry_msgs::msg::TwistStamped();
322 command_->header.stamp = now();
328 geometry_msgs::msg::TwistStamped current_;
330 current_ = last_cmd_;
332 current_ = odom_smoother_->getTwistStamped();
336 command_->twist.linear.x = std::clamp(
337 command_->twist.linear.x, min_velocities_[0],
339 command_->twist.linear.y = std::clamp(
340 command_->twist.linear.y, min_velocities_[1],
342 command_->twist.angular.z = std::clamp(
343 command_->twist.angular.z, min_velocities_[2],
352 if (scale_velocities_) {
353 double curr_eta = -1.0;
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)) {
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)) {
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)) {
375 current_.twist.linear.x, command_->twist.linear.x, max_accels_[0], max_decels_[0], eta);
377 current_.twist.linear.y, command_->twist.linear.y, max_accels_[1], max_decels_[1], eta);
379 current_.twist.angular.z, command_->twist.angular.z, max_accels_[2], max_decels_[2], eta);
380 last_cmd_ = *cmd_vel;
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;
390 smoothed_cmd_pub_->publish(std::move(cmd_vel));
393 rcl_interfaces::msg::SetParametersResult
396 rcl_interfaces::msg::SetParametersResult result;
397 result.successful =
true;
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) {
406 if (param_type == ParameterType::PARAMETER_DOUBLE) {
407 if (param_name ==
"smoothing_frequency") {
408 smoothing_frequency_ = parameter.as_double();
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)),
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();
423 std::make_unique<nav2_util::OdomSmoother>(
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",
430 result.successful =
false;
434 if (param_name ==
"max_velocity") {
435 for (
unsigned int i = 0; i != 3; i++) {
436 if (parameter.as_double_array()[i] < 0.0) {
439 "Negative values set of max_velocity! These should be positive!");
440 result.successful =
false;
443 if (result.successful) {
444 max_velocities_ = parameter.as_double_array();
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) {
451 "Positive values set of min_velocity! These should be negative!");
452 result.successful =
false;
455 if (result.successful) {
456 min_velocities_ = parameter.as_double_array();
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) {
463 "Negative values set of acceleration! These should be positive to speed up!");
464 result.successful =
false;
467 if (result.successful) {
468 max_accels_ = parameter.as_double_array();
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) {
475 "Positive values set of deceleration! These should be negative to slow down!");
476 result.successful =
false;
479 if (result.successful) {
480 max_decels_ = parameter.as_double_array();
482 }
else if (param_name ==
"deadband_velocity") {
483 deadband_velocities_ = parameter.as_double_array();
485 }
else if (param_type == ParameterType::PARAMETER_STRING) {
486 if (param_name ==
"feedback") {
487 if (parameter.as_string() ==
"OPEN_LOOP") {
489 odom_smoother_.reset();
490 }
else if (parameter.as_string() ==
"CLOSED_LOOP") {
493 std::make_unique<nav2_util::OdomSmoother>(
497 get_logger(),
"Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
498 result.successful =
false;
501 }
else if (param_name ==
"odom_topic") {
502 odom_topic_ = parameter.as_string();
504 std::make_unique<nav2_util::OdomSmoother>(
515 #include "rclcpp_components/register_node_macro.hpp"
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.