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

Re-add Clock::sleep_until #1814

Merged
merged 16 commits into from
Nov 5, 2021
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
25 changes: 25 additions & 0 deletions rclcpp/include/rclcpp/clock.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <memory>
#include <mutex>

#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/visibility_control.hpp"
Expand Down Expand Up @@ -78,6 +79,30 @@ class Clock
Time
now();

/**
* Sleep until a specified Time, according to clock type.
*
* Notes for RCL_ROS_TIME clock type:
* - Can sleep forever if ros time is active and received clock never reaches `until`
* - If ROS time enabled state changes during the sleep, this method will immediately return
* false. There is not a consistent choice of sleeping time when the time source changes,
* so this is up to the caller to call again if needed.
*
* \param until absolute time according to current clock type to sleep until.
* \param context the rclcpp context the clock should use to check that ROS is still initialized.
* \return true immediately if `until` is in the past
* \return true when the time `until` is reached
* \return false if time cannot be reached reliably, for example from shutdown or a change
* of time source.
* \throws std::runtime_error if the context is invalid
* \throws std::runtime_error if `until` has a different clock type from this clock
*/
RCLCPP_PUBLIC
bool
sleep_until(
Time until,
Context::SharedPtr context = contexts::get_global_default_context());

/**
* Returns the clock of the type `RCL_ROS_TIME` is active.
*
Expand Down
96 changes: 96 additions & 0 deletions rclcpp/src/rclcpp/clock.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,14 @@

#include "rclcpp/clock.hpp"

#include <condition_variable>
#include <memory>
#include <thread>

#include "rclcpp/exceptions.hpp"
#include "rclcpp/utilities.hpp"

#include "rcpputils/scope_exit.hpp"
#include "rcutils/logging_macros.h"

namespace rclcpp
Expand Down Expand Up @@ -76,6 +79,99 @@ Clock::now()
return now;
}

bool
Clock::sleep_until(Time until, Context::SharedPtr context)
{
if (!context || !context->is_valid()) {
throw std::runtime_error("context cannot be slept with because it's invalid");
}
const auto this_clock_type = get_clock_type();
if (until.get_clock_type() != this_clock_type) {
throw std::runtime_error("until's clock type does not match this clock's type");
}
bool time_source_changed = false;

std::condition_variable cv;

// Wake this thread if the context is shutdown
rclcpp::OnShutdownCallbackHandle shutdown_cb_handle = context->add_on_shutdown_callback(
[&cv]() {
cv.notify_one();
});
// No longer need the shutdown callback when this function exits
auto callback_remover = rcpputils::scope_exit(
[context, &shutdown_cb_handle]() {
context->remove_on_shutdown_callback(shutdown_cb_handle);
});

if (this_clock_type == RCL_STEADY_TIME) {
auto steady_time = std::chrono::steady_clock::time_point(
std::chrono::nanoseconds(until.nanoseconds()));

// loop over spurious wakeups but notice shutdown
std::unique_lock lock(impl_->clock_mutex_);
while (now() < until && context->is_valid()) {
cv.wait_until(lock, steady_time);
}
} else if (this_clock_type == RCL_SYSTEM_TIME) {
auto system_time = std::chrono::system_clock::time_point(
// Cast because system clock resolution is too big for nanoseconds on some systems
std::chrono::duration_cast<std::chrono::system_clock::duration>(
std::chrono::nanoseconds(until.nanoseconds())));

// loop over spurious wakeups but notice shutdown
std::unique_lock lock(impl_->clock_mutex_);
while (now() < until && context->is_valid()) {
cv.wait_until(lock, system_time);
}
} else if (this_clock_type == RCL_ROS_TIME) {
// Install jump handler for any amount of time change, for two purposes:
// - if ROS time is active, check if time reached on each new clock sample
// - Trigger via on_clock_change to detect if time source changes, to invalidate sleep
rcl_jump_threshold_t threshold;
threshold.on_clock_change = true;
// 0 is disable, so -1 and 1 are smallest possible time changes
threshold.min_backward.nanoseconds = -1;
threshold.min_forward.nanoseconds = 1;
auto clock_handler = create_jump_callback(
nullptr,
[&cv, &time_source_changed](const rcl_time_jump_t & jump) {
if (jump.clock_change != RCL_ROS_TIME_NO_CHANGE) {
time_source_changed = true;
}
cv.notify_one();
},
threshold);

if (!ros_time_is_active()) {
auto system_time = std::chrono::system_clock::time_point(
// Cast because system clock resolution is too big for nanoseconds on some systems
std::chrono::duration_cast<std::chrono::system_clock::duration>(
std::chrono::nanoseconds(until.nanoseconds())));

// loop over spurious wakeups but notice shutdown or time source change
std::unique_lock lock(impl_->clock_mutex_);
while (now() < until && context->is_valid() && !time_source_changed) {
cv.wait_until(lock, system_time);
}
} else {
// RCL_ROS_TIME with ros_time_is_active.
// Just wait without "until" because installed
// jump callbacks wake the cv on every new sample.
std::unique_lock lock(impl_->clock_mutex_);
while (now() < until && context->is_valid() && !time_source_changed) {
cv.wait(lock);
}
}
}

if (!context->is_valid() || time_source_changed) {
return false;
}

return now() >= until;
}

bool
Clock::ros_time_is_active()
{
Expand Down
Loading