diff --git a/nav2_velocity_smoother/src/velocity_smoother.cpp b/nav2_velocity_smoother/src/velocity_smoother.cpp index 0f7ee04f14..2596c073ba 100644 --- a/nav2_velocity_smoother/src/velocity_smoother.cpp +++ b/nav2_velocity_smoother/src/velocity_smoother.cpp @@ -305,13 +305,14 @@ void VelocitySmoother::smootherTimer() current_.linear.y, command_->linear.y, max_accels_[1], max_decels_[1], eta); cmd_vel->angular.z = applyConstraints( current_.angular.z, command_->angular.z, max_accels_[2], max_decels_[2], eta); + 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)); }