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) {
79 throw std::runtime_error(
80 "Positive values set of deceleration! These should be negative to slow down!");
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!");
86 if (min_velocities_[i] > max_velocities_[i]) {
87 throw std::runtime_error(
88 "Min velocities are higher than max velocities!");
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);
104 if (max_velocities_.size() != 3 || min_velocities_.size() != 3 ||
105 max_accels_.size() != 3 || max_decels_.size() != 3 || deadband_velocities_.size() != 3)
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).");
113 if (feedback_type ==
"OPEN_LOOP") {
115 }
else if (feedback_type ==
"CLOSED_LOOP") {
117 odom_smoother_ = std::make_unique<nav2_util::OdomSmoother>(node, odom_duration_, odom_topic_);
119 throw std::runtime_error(
"Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
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),
128 return nav2_util::CallbackReturn::SUCCESS;
131 nav2_util::CallbackReturn
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)),
141 dyn_params_handler_ = this->add_on_set_parameters_callback(
146 return nav2_util::CallbackReturn::SUCCESS;
149 nav2_util::CallbackReturn
152 RCLCPP_INFO(get_logger(),
"Deactivating");
157 smoothed_cmd_pub_->on_deactivate();
158 dyn_params_handler_.reset();
162 return nav2_util::CallbackReturn::SUCCESS;
165 nav2_util::CallbackReturn
168 RCLCPP_INFO(get_logger(),
"Cleaning up");
169 smoothed_cmd_pub_.reset();
170 odom_smoother_.reset();
172 return nav2_util::CallbackReturn::SUCCESS;
175 nav2_util::CallbackReturn
178 RCLCPP_INFO(get_logger(),
"Shutting down");
179 return nav2_util::CallbackReturn::SUCCESS;
185 if (!nav2_util::validateTwist(*msg)) {
186 RCLCPP_ERROR(get_logger(),
"Velocity message contains NaNs or Infs! Ignoring as invalid!");
191 last_command_time_ = now();
195 const double v_curr,
const double v_cmd,
const double accel,
const double decel)
198 double dv = v_cmd - v_curr;
200 double v_component_max;
201 double v_component_min;
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_;
210 v_component_max = -decel / smoothing_frequency_;
211 v_component_min = decel / smoothing_frequency_;
214 if (dv > v_component_max) {
215 return v_component_max / dv;
218 if (dv < v_component_min) {
219 return v_component_min / dv;
226 const double v_curr,
const double v_cmd,
227 const double accel,
const double decel,
const double eta)
229 double dv = v_cmd - v_curr;
231 double v_component_max;
232 double v_component_min;
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_;
241 v_component_max = -decel / smoothing_frequency_;
242 v_component_min = decel / smoothing_frequency_;
245 return v_curr + std::clamp(eta * dv, v_component_min, v_component_max);
255 auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>();
258 if (now() - last_command_time_ > velocity_timeout_) {
259 if (last_cmd_ == geometry_msgs::msg::Twist() || stopped_) {
263 *command_ = geometry_msgs::msg::Twist();
269 geometry_msgs::msg::Twist current_;
271 current_ = last_cmd_;
273 current_ = odom_smoother_->getTwist();
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]);
287 if (scale_velocities_) {
288 double curr_eta = -1.0;
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)) {
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)) {
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)) {
310 current_.linear.x, command_->linear.x, max_accels_[0], max_decels_[0], eta);
312 current_.linear.y, command_->linear.y, max_accels_[1], max_decels_[1], eta);
314 current_.angular.z, command_->angular.z, max_accels_[2], max_decels_[2], eta);
315 last_cmd_ = *cmd_vel;
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;
323 smoothed_cmd_pub_->publish(std::move(cmd_vel));
326 rcl_interfaces::msg::SetParametersResult
329 rcl_interfaces::msg::SetParametersResult result;
330 result.successful =
true;
332 for (
auto parameter : parameters) {
333 const auto & type = parameter.get_type();
334 const auto & name = parameter.get_name();
336 if (type == ParameterType::PARAMETER_DOUBLE) {
337 if (name ==
"smoothing_frequency") {
338 smoothing_frequency_ = parameter.as_double();
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)),
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();
353 std::make_unique<nav2_util::OdomSmoother>(
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;
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) {
372 "Negative values set of acceleration! These should be positive to speed up!");
373 result.successful =
false;
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) {
382 "Positive values set of deceleration! These should be negative to slow down!");
383 result.successful =
false;
386 max_decels_ = parameter.as_double_array();
387 }
else if (name ==
"deadband_velocity") {
388 deadband_velocities_ = parameter.as_double_array();
390 }
else if (type == ParameterType::PARAMETER_STRING) {
391 if (name ==
"feedback") {
392 if (parameter.as_string() ==
"OPEN_LOOP") {
394 odom_smoother_.reset();
395 }
else if (parameter.as_string() ==
"CLOSED_LOOP") {
398 std::make_unique<nav2_util::OdomSmoother>(
402 get_logger(),
"Invalid feedback_type, options are OPEN_LOOP and CLOSED_LOOP.");
403 result.successful =
false;
406 }
else if (name ==
"odom_topic") {
407 odom_topic_ = parameter.as_string();
409 std::make_unique<nav2_util::OdomSmoother>(
420 #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.