diff --git a/nav2_recoveries/plugins/wait.cpp b/nav2_recoveries/plugins/wait.cpp index 7964103b3c..10dcc19709 100644 --- a/nav2_recoveries/plugins/wait.cpp +++ b/nav2_recoveries/plugins/wait.cpp @@ -24,7 +24,6 @@ namespace nav2_recoveries Wait::Wait() : Recovery() { - duration_.sec = 0.0; } Wait::~Wait() @@ -33,15 +32,22 @@ Wait::~Wait() Status Wait::onRun(const std::shared_ptr command) { - duration_ = command->time; + wait_end_ = std::chrono::steady_clock::now() + + rclcpp::Duration(command->time).to_chrono(); return Status::SUCCEEDED; } Status Wait::onCycleUpdate() { - rclcpp::sleep_for( - rclcpp::Duration(duration_).to_chrono()); - return Status::SUCCEEDED; + auto current_point = std::chrono::steady_clock::now(); + auto time_left = + std::chrono::duration_cast(wait_end_ - current_point).count(); + + if (time_left > 0) { + return Status::RUNNING; + } else { + return Status::SUCCEEDED; + } } } // namespace nav2_recoveries diff --git a/nav2_recoveries/plugins/wait.hpp b/nav2_recoveries/plugins/wait.hpp index 4f883220d6..af337d3c94 100644 --- a/nav2_recoveries/plugins/wait.hpp +++ b/nav2_recoveries/plugins/wait.hpp @@ -37,7 +37,7 @@ class Wait : public Recovery Status onCycleUpdate() override; protected: - builtin_interfaces::msg::Duration duration_; + std::chrono::time_point wait_end_; }; } // namespace nav2_recoveries