Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Velocity smoother] Set zeros command if timeout #3512

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 6 additions & 11 deletions nav2_velocity_smoother/src/velocity_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -216,14 +216,13 @@ void VelocitySmoother::smootherTimer()

auto cmd_vel = std::make_unique<geometry_msgs::msg::Twist>();

// 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;
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
}
stopped_ = true;
return;
*command_ = geometry_msgs::msg::Twist();
}

stopped_ = false;
Expand Down Expand Up @@ -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));
}

Expand Down