diff --git a/nav2_velocity_smoother/src/velocity_smoother.cpp b/nav2_velocity_smoother/src/velocity_smoother.cpp index 17c9ee718d1..1c42ff44fb2 100644 --- a/nav2_velocity_smoother/src/velocity_smoother.cpp +++ b/nav2_velocity_smoother/src/velocity_smoother.cpp @@ -216,14 +216,13 @@ void VelocitySmoother::smootherTimer() auto cmd_vel = std::make_unique(); - // Check for velocity timeout. If nothing received, publish zeros to stop robot + // Check for velocity timeout. If nothing received, publish zeros to apply deceleration if (now() - last_command_time_ > velocity_timeout_) { - last_cmd_ = geometry_msgs::msg::Twist(); - if (!stopped_) { - smoothed_cmd_pub_->publish(std::move(cmd_vel)); + if (last_cmd_ == geometry_msgs::msg::Twist() || stopped_) { + stopped_ = true; + return; } - stopped_ = true; - return; + *command_ = geometry_msgs::msg::Twist(); } stopped_ = false; @@ -276,16 +275,12 @@ void VelocitySmoother::smootherTimer() cmd_vel->angular.z = applyConstraints( current_.angular.z, command_->angular.z, max_accels_[2], max_decels_[2], eta); - // If open loop, assume we achieved it - if (open_loop_) { - last_cmd_ = *cmd_vel; - } - // Apply deadband restrictions & publish cmd_vel->linear.x = fabs(cmd_vel->linear.x) < deadband_velocities_[0] ? 0.0 : cmd_vel->linear.x; cmd_vel->linear.y = fabs(cmd_vel->linear.y) < deadband_velocities_[1] ? 0.0 : cmd_vel->linear.y; cmd_vel->angular.z = fabs(cmd_vel->angular.z) < deadband_velocities_[2] ? 0.0 : cmd_vel->angular.z; + last_cmd_ = *cmd_vel; smoothed_cmd_pub_->publish(std::move(cmd_vel)); }