Skip to content

Commit

Permalink
Fix nav2_velocity_smoother for sim time (ros-navigation#3360)
Browse files Browse the repository at this point in the history
* Fix nav2_velocity_smoother for sim time

* Update nav2_velocity_smoother/src/velocity_smoother.cpp

Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
  • Loading branch information
2 people authored and Andrew Lycas committed Feb 23, 2023
1 parent 2dbd752 commit c07a6fe
Showing 1 changed file with 5 additions and 0 deletions.
5 changes: 5 additions & 0 deletions nav2_velocity_smoother/src/velocity_smoother.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,11 @@ double VelocitySmoother::applyConstraints(

void VelocitySmoother::smootherTimer()
{
// Wait until the first command is received
if (!command_) {
return;
}

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

// Check for velocity timeout. If nothing received, publish zeros to stop robot
Expand Down

0 comments on commit c07a6fe

Please sign in to comment.