Class Clock

Class Documentation

class Clock

Public Functions

explicit Clock(rcl_clock_type_t clock_type = RCL_SYSTEM_TIME)

Default c’tor.

Initializes the clock instance with the given clock_type.

Parameters:

clock_type – type of the clock.

Throws:

anythingrclcpp::exceptions::throw_from_rcl_error can throw.

~Clock()
Time now() const

Returns current time from the time source specified by clock_type.

Throws:

anythingrclcpp::exceptions::throw_from_rcl_error can throw.

Returns:

current time.

bool sleep_until(Time until, Context::SharedPtr context = contexts::get_global_default_context())

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.

Warning

When using gcc < 10 or when using gcc >= 10 and pthreads lacks the function pthread_cond_clockwait, steady clocks may sleep using the system clock. If so, steady clock sleep times can be affected by system clock time jumps. Depending on the steady clock’s epoch and resolution in comparison to the system clock’s, an overflow when converting steady clock durations to system clock times may cause undefined behavior. For more info see these issues: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=41861 https://gcc.gnu.org/bugzilla/show_bug.cgi?id=58931

Parameters:
  • until – absolute time according to current clock type to sleep until.

  • context – the rclcpp context the clock should use to check that ROS is still initialized.

Throws:
  • std::runtime_error – if the context is invalid

  • std::runtime_error – if until has a different clock type from this clock

Returns:

true immediately if until is in the past

Returns:

true when the time until is reached

Returns:

false if time cannot be reached reliably, for example from shutdown or a change of time source.

bool sleep_for(Duration rel_time, Context::SharedPtr context = contexts::get_global_default_context())

Sleep for a specified Duration.

Equivalent to

clock->sleep_until(clock->now() + rel_time, context)

The function will return immediately if rel_time is zero or negative.

Parameters:
  • rel_time – the length of time to sleep for.

  • context – the rclcpp context the clock should use to check that ROS is still initialized.

Throws:

std::runtime_error – if the context is invalid

Returns:

true when the end time is reached

Returns:

false if time cannot be reached reliably, for example from shutdown or a change of time source.

bool started()

Check if the clock is started.

A started clock is a clock that reflects non-zero time. Typically a clock will be unstarted if it is using RCL_ROS_TIME with ROS time and nothing has been published on the clock topic yet.

Throws:

std::runtime_error – if the clock is not rcl_clock_valid

Returns:

true if clock is started

bool wait_until_started(Context::SharedPtr context = contexts::get_global_default_context())

Wait until clock to start.

\rclcppClock::started

Parameters:

context – the context to wait in

Throws:

std::runtime_error – if the context is invalid or clock is not rcl_clock_valid

Returns:

true if clock was already started or became started

bool wait_until_started(const rclcpp::Duration &timeout, Context::SharedPtr context = contexts::get_global_default_context(), const rclcpp::Duration &wait_tick_ns = rclcpp::Duration(0, static_cast<uint32_t>(1e7)))

Wait for clock to start, with timeout.

The timeout is waited in steady time.

\rclcppClock::started

Parameters:
  • timeout – the maximum time to wait for.

  • context – the context to wait in.

  • wait_tick_ns – the time to wait between each iteration of the wait loop (in nanoseconds).

Throws:

std::runtime_error – if the context is invalid or clock is not rcl_clock_valid

Returns:

true if clock was or became valid

bool ros_time_is_active()

Returns the clock of the type RCL_ROS_TIME is active.

Throws:

anythingrclcpp::exceptions::throw_from_rcl_error can throw if the current clock does not have the clock_type RCL_ROS_TIME.

Returns:

true if the clock is active

void cancel_sleep_or_wait()

Cancels an ongoing or future sleep operation of one thread.

This function can be used by one thread, to wakeup another thread that is blocked using any of the sleep_ or wait_ methods of this class.

rcl_clock_t *get_clock_handle() noexcept

Return the rcl_clock_t clock handle.

rcl_clock_type_t get_clock_type() const noexcept
std::mutex &get_clock_mutex() noexcept

Get the clock’s mutex.

JumpHandler::SharedPtr create_jump_callback(JumpHandler::pre_callback_t pre_callback, JumpHandler::post_callback_t post_callback, const rcl_jump_threshold_t &threshold)

These callback functions must remain valid as long as the returned shared pointer is valid.

Function will register callbacks to the callback queue. On time jump all callbacks will be executed whose threshold is greater then the time jump; The logic will first call selected pre_callbacks and then all selected post_callbacks.

Function is only applicable if the clock_type is RCL_ROS_TIME

Warning

the instance of the clock must remain valid as long as any created JumpHandler.

Parameters:
  • pre_callback – Must be non-throwing

  • post_callback – Must be non-throwing.

  • threshold – Callbacks will be triggered if the time jump is greater then the threshold.

Throws: