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

Allow reaction to cancellation and preemption on wait recovery plugin #1636

Merged
merged 2 commits into from
Apr 15, 2020
Merged
Show file tree
Hide file tree
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
16 changes: 11 additions & 5 deletions nav2_recoveries/plugins/wait.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ namespace nav2_recoveries
Wait::Wait()
: Recovery<WaitAction>()
{
duration_.sec = 0.0;
}

Wait::~Wait()
Expand All @@ -33,15 +32,22 @@ Wait::~Wait()

Status Wait::onRun(const std::shared_ptr<const WaitAction::Goal> command)
{
duration_ = command->time;
wait_end_ = std::chrono::steady_clock::now() +
rclcpp::Duration(command->time).to_chrono<std::chrono::nanoseconds>();
return Status::SUCCEEDED;
}

Status Wait::onCycleUpdate()
{
rclcpp::sleep_for(
rclcpp::Duration(duration_).to_chrono<std::chrono::nanoseconds>());
return Status::SUCCEEDED;
auto current_point = std::chrono::steady_clock::now();
auto time_left =
std::chrono::duration_cast<std::chrono::nanoseconds>(wait_end_ - current_point).count();

if (time_left > 0) {
return Status::RUNNING;
} else {
return Status::SUCCEEDED;
}
}

} // namespace nav2_recoveries
Expand Down
2 changes: 1 addition & 1 deletion nav2_recoveries/plugins/wait.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class Wait : public Recovery<WaitAction>
Status onCycleUpdate() override;

protected:
builtin_interfaces::msg::Duration duration_;
std::chrono::time_point<std::chrono::steady_clock> wait_end_;
};

} // namespace nav2_recoveries
Expand Down