ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
clock.cpp
1 // Copyright 2017 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "rclcpp/clock.hpp"
16 
17 #include <condition_variable>
18 #include <memory>
19 #include <thread>
20 
21 #include "rclcpp/exceptions.hpp"
22 #include "rclcpp/utilities.hpp"
23 
24 #include "rcpputils/scope_exit.hpp"
25 #include "rcutils/logging_macros.h"
26 
27 namespace rclcpp
28 {
29 
31 {
32 public:
33  explicit Impl(rcl_clock_type_t clock_type)
34  : allocator_{rcl_get_default_allocator()}
35  {
36  rcl_ret_t ret = rcl_clock_init(clock_type, &rcl_clock_, &allocator_);
37  if (ret != RCL_RET_OK) {
38  exceptions::throw_from_rcl_error(ret, "failed to initialize rcl clock");
39  }
40  }
41 
42  ~Impl()
43  {
44  rcl_ret_t ret = rcl_clock_fini(&rcl_clock_);
45  if (ret != RCL_RET_OK) {
46  RCUTILS_LOG_ERROR("Failed to fini rcl clock.");
47  }
48  }
49 
50  rcl_clock_t rcl_clock_;
51  rcl_allocator_t allocator_;
52  bool stop_sleeping_ = false;
53  bool shutdown_ = false;
54  std::condition_variable cv_;
55  std::mutex wait_mutex_;
56  std::mutex clock_mutex_;
57 };
58 
59 JumpHandler::JumpHandler(
60  pre_callback_t pre_callback,
61  post_callback_t post_callback,
62  const rcl_jump_threshold_t & threshold)
63 : pre_callback(pre_callback),
64  post_callback(post_callback),
65  notice_threshold(threshold)
66 {}
67 
69 : impl_(new Clock::Impl(clock_type)) {}
70 
71 Clock::~Clock() {}
72 
73 Time
74 Clock::now() const
75 {
76  Time now(0, 0, impl_->rcl_clock_.type);
77 
78  auto ret = rcl_clock_get_now(&impl_->rcl_clock_, &now.rcl_time_.nanoseconds);
79  if (ret != RCL_RET_OK) {
80  exceptions::throw_from_rcl_error(ret, "could not get current time stamp");
81  }
82 
83  return now;
84 }
85 
86 void
88 {
89  {
90  std::unique_lock lock(impl_->wait_mutex_);
91  impl_->stop_sleeping_ = true;
92  }
93  impl_->cv_.notify_one();
94 }
95 
96 bool
98  Time until,
99  Context::SharedPtr context)
100 {
101  if (!context || !context->is_valid()) {
102  throw std::runtime_error("context cannot be slept with because it's invalid");
103  }
104  const auto this_clock_type = get_clock_type();
105  if (until.get_clock_type() != this_clock_type) {
106  throw std::runtime_error("until's clock type does not match this clock's type");
107  }
108  bool time_source_changed = false;
109 
110  // Wake this thread if the context is shutdown
111  rclcpp::OnShutdownCallbackHandle shutdown_cb_handle = context->add_on_shutdown_callback(
112  [this]() {
113  {
114  std::unique_lock lock(impl_->wait_mutex_);
115  impl_->shutdown_ = true;
116  }
117  impl_->cv_.notify_one();
118  });
119  // No longer need the shutdown callback when this function exits
120  auto callback_remover = rcpputils::scope_exit(
121  [&context, &shutdown_cb_handle]() {
122  context->remove_on_shutdown_callback(shutdown_cb_handle);
123  });
124 
125  if (this_clock_type == RCL_STEADY_TIME) {
126  // Synchronize because RCL steady clock epoch might differ from chrono::steady_clock epoch
127  const Time rcl_entry = now();
128  const std::chrono::steady_clock::time_point chrono_entry = std::chrono::steady_clock::now();
129  const Duration delta_t = until - rcl_entry;
130  const std::chrono::steady_clock::time_point chrono_until =
131  chrono_entry + std::chrono::nanoseconds(delta_t.nanoseconds());
132 
133  // loop over spurious wakeups but notice shutdown or stop of sleep
134  std::unique_lock lock(impl_->wait_mutex_);
135  while (now() < until && !impl_->stop_sleeping_ && !impl_->shutdown_ && context->is_valid()) {
136  impl_->cv_.wait_until(lock, chrono_until);
137  }
138  impl_->stop_sleeping_ = false;
139  } else if (this_clock_type == RCL_SYSTEM_TIME) {
140  auto system_time = std::chrono::system_clock::time_point(
141  // Cast because system clock resolution is too big for nanoseconds on some systems
142  std::chrono::duration_cast<std::chrono::system_clock::duration>(
143  std::chrono::nanoseconds(until.nanoseconds())));
144 
145  // loop over spurious wakeups but notice shutdown or stop of sleep
146  std::unique_lock lock(impl_->wait_mutex_);
147  while (now() < until && !impl_->stop_sleeping_ && !impl_->shutdown_ && context->is_valid()) {
148  impl_->cv_.wait_until(lock, system_time);
149  }
150  impl_->stop_sleeping_ = false;
151  } else if (this_clock_type == RCL_ROS_TIME) {
152  // Install jump handler for any amount of time change, for two purposes:
153  // - if ROS time is active, check if time reached on each new clock sample
154  // - Trigger via on_clock_change to detect if time source changes, to invalidate sleep
155  rcl_jump_threshold_t threshold;
156  threshold.on_clock_change = true;
157  // 0 is disable, so -1 and 1 are smallest possible time changes
158  threshold.min_backward.nanoseconds = -1;
159  threshold.min_forward.nanoseconds = 1;
160  auto clock_handler = create_jump_callback(
161  nullptr,
162  [this, &time_source_changed](const rcl_time_jump_t & jump) {
163  if (jump.clock_change != RCL_ROS_TIME_NO_CHANGE) {
164  std::lock_guard<std::mutex> lk(impl_->wait_mutex_);
165  time_source_changed = true;
166  }
167  impl_->cv_.notify_one();
168  },
169  threshold);
170 
171  if (!ros_time_is_active()) {
172  auto system_time = std::chrono::system_clock::time_point(
173  // Cast because system clock resolution is too big for nanoseconds on some systems
174  std::chrono::duration_cast<std::chrono::system_clock::duration>(
175  std::chrono::nanoseconds(until.nanoseconds())));
176 
177  // loop over spurious wakeups but notice shutdown, stop of sleep or time source change
178  std::unique_lock lock(impl_->wait_mutex_);
179  while (now() < until && !impl_->stop_sleeping_ && !impl_->shutdown_ && context->is_valid() &&
180  !time_source_changed)
181  {
182  impl_->cv_.wait_until(lock, system_time);
183  }
184  impl_->stop_sleeping_ = false;
185  } else {
186  // RCL_ROS_TIME with ros_time_is_active.
187  // Just wait without "until" because installed
188  // jump callbacks wake the cv on every new sample.
189  std::unique_lock lock(impl_->wait_mutex_);
190  while (now() < until && !impl_->stop_sleeping_ && !impl_->shutdown_ && context->is_valid() &&
191  !time_source_changed)
192  {
193  impl_->cv_.wait(lock);
194  }
195  impl_->stop_sleeping_ = false;
196  }
197  }
198 
199  if (!context->is_valid() || time_source_changed) {
200  return false;
201  }
202 
203  return now() >= until;
204 }
205 
206 bool
207 Clock::sleep_for(Duration rel_time, Context::SharedPtr context)
208 {
209  return sleep_until(now() + rel_time, context);
210 }
211 
212 bool
214 {
216  throw std::runtime_error("clock is not rcl_clock_valid");
217  }
219 }
220 
221 bool
222 Clock::wait_until_started(Context::SharedPtr context)
223 {
224  if (!context || !context->is_valid()) {
225  throw std::runtime_error("context cannot be slept with because it's invalid");
226  }
228  throw std::runtime_error("clock cannot be waited on as it is not rcl_clock_valid");
229  }
230 
231  if (started()) {
232  return true;
233  } else {
234  // Wait until the first non-zero time
235  return sleep_until(rclcpp::Time(0, 1, get_clock_type()), context);
236  }
237 }
238 
239 bool
241  const Duration & timeout,
242  Context::SharedPtr context,
243  const Duration & wait_tick_ns)
244 {
245  if (!context || !context->is_valid()) {
246  throw std::runtime_error("context cannot be slept with because it's invalid");
247  }
249  throw std::runtime_error("clock cannot be waited on as it is not rcl_clock_valid");
250  }
251 
252  Clock timeout_clock = Clock(RCL_STEADY_TIME);
253  Time start = timeout_clock.now();
254 
255  // Check if the clock has started every wait_tick_ns nanoseconds
256  // Context check checks for rclcpp::shutdown()
257  while (!started() && context->is_valid()) {
258  if (timeout < wait_tick_ns) {
259  timeout_clock.sleep_for(timeout);
260  } else {
261  Duration time_left = start + timeout - timeout_clock.now();
262  if (time_left > wait_tick_ns) {
263  timeout_clock.sleep_for(Duration(wait_tick_ns));
264  } else {
265  timeout_clock.sleep_for(time_left);
266  }
267  }
268 
269  if (timeout_clock.now() - start > timeout) {
270  return started();
271  }
272  }
273  return started();
274 }
275 
276 
277 bool
279 {
280  if (!rcl_clock_valid(&impl_->rcl_clock_)) {
281  RCUTILS_LOG_ERROR("ROS time not valid!");
282  return false;
283  }
284 
285  bool is_enabled = false;
286  auto ret = rcl_is_enabled_ros_time_override(&impl_->rcl_clock_, &is_enabled);
287  if (ret != RCL_RET_OK) {
288  exceptions::throw_from_rcl_error(
289  ret, "Failed to check ros_time_override_status");
290  }
291  return is_enabled;
292 }
293 
294 rcl_clock_t *
296 {
297  return &impl_->rcl_clock_;
298 }
299 
301 Clock::get_clock_type() const noexcept
302 {
303  return impl_->rcl_clock_.type;
304 }
305 
306 std::mutex &
308 {
309  return impl_->clock_mutex_;
310 }
311 
312 void
313 Clock::on_time_jump(
314  const rcl_time_jump_t * time_jump,
315  bool before_jump,
316  void * user_data)
317 {
318  const auto * handler = static_cast<JumpHandler *>(user_data);
319  if (nullptr == handler) {
320  return;
321  }
322  if (before_jump && handler->pre_callback) {
323  handler->pre_callback();
324  } else if (!before_jump && handler->post_callback) {
325  handler->post_callback(*time_jump);
326  }
327 }
328 
329 JumpHandler::SharedPtr
331  JumpHandler::pre_callback_t pre_callback,
332  JumpHandler::post_callback_t post_callback,
333  const rcl_jump_threshold_t & threshold)
334 {
335  // Allocate a new jump handler
336  JumpHandler::UniquePtr handler(new JumpHandler(pre_callback, post_callback, threshold));
337  if (nullptr == handler) {
338  throw std::bad_alloc{};
339  }
340 
341  {
342  std::lock_guard<std::mutex> clock_guard(impl_->clock_mutex_);
343  // Try to add the jump callback to the clock
345  &impl_->rcl_clock_, threshold, Clock::on_time_jump,
346  handler.get());
347  if (RCL_RET_OK != ret) {
348  exceptions::throw_from_rcl_error(ret, "Failed to add time jump callback");
349  }
350  }
351 
352  std::weak_ptr<Clock::Impl> weak_impl = impl_;
353  // *INDENT-OFF*
354  // create shared_ptr that removes the callback automatically when all copies are destructed
355  return JumpHandler::SharedPtr(handler.release(), [weak_impl](JumpHandler * handler) noexcept {
356  auto shared_impl = weak_impl.lock();
357  if (shared_impl) {
358  std::lock_guard<std::mutex> clock_guard(shared_impl->clock_mutex_);
359  rcl_ret_t ret = rcl_clock_remove_jump_callback(&shared_impl->rcl_clock_,
360  Clock::on_time_jump, handler);
361  if (RCL_RET_OK != ret) {
362  RCUTILS_LOG_ERROR("Failed to remove time jump callback");
363  }
364  }
365  delete handler;
366  });
367  // *INDENT-ON*
368 }
369 
371 {
372 private:
373  std::condition_variable cv_;
374 
375  rclcpp::Clock::SharedPtr clock_;
376  bool time_source_changed_ = false;
377  std::function<void(const rcl_time_jump_t &)> post_time_jump_callback;
378 
379  bool
380  wait_until_system_time(
381  std::unique_lock<std::mutex> & lock,
382  const rclcpp::Time & abs_time, const std::function<bool ()> & pred)
383  {
384  auto system_time = std::chrono::system_clock::time_point(
385  // Cast because system clock resolution is too big for nanoseconds on some systems
386  std::chrono::duration_cast<std::chrono::system_clock::duration>(
387  std::chrono::nanoseconds(abs_time.nanoseconds())));
388 
389  return cv_.wait_until(lock, system_time, pred);
390  }
391 
392  bool
393  wait_until_steady_time(
394  std::unique_lock<std::mutex> & lock,
395  const rclcpp::Time & abs_time, const std::function<bool ()> & pred)
396  {
397  // Synchronize because RCL steady clock epoch might differ from chrono::steady_clock epoch
398  const rclcpp::Time rcl_entry = clock_->now();
399  const std::chrono::steady_clock::time_point chrono_entry = std::chrono::steady_clock::now();
400  const rclcpp::Duration delta_t = abs_time - rcl_entry;
401  const std::chrono::steady_clock::time_point chrono_until =
402  chrono_entry + std::chrono::nanoseconds(delta_t.nanoseconds());
403 
404  return cv_.wait_until(lock, chrono_until, pred);
405  }
406 
407 
408  bool
409  wait_until_ros_time(
410  std::unique_lock<std::mutex> & lock,
411  const rclcpp::Time & abs_time, const std::function<bool ()> & pred)
412  {
413  // Install jump handler for any amount of time change, for two purposes:
414  // - if ROS time is active, check if time reached on each new clock sample
415  // - Trigger via on_clock_change to detect if time source changes, to invalidate sleep
416  rcl_jump_threshold_t threshold;
417  threshold.on_clock_change = true;
418  // 0 is disable, so -1 and 1 are smallest possible time changes
419  threshold.min_backward.nanoseconds = -1;
420  threshold.min_forward.nanoseconds = 1;
421 
422  time_source_changed_ = false;
423 
424  post_time_jump_callback = [this, &lock] (const rcl_time_jump_t & jump)
425  {
426  if (jump.clock_change != RCL_ROS_TIME_NO_CHANGE) {
427  std::lock_guard<std::mutex> lk(*lock.mutex());
428  time_source_changed_ = true;
429  }
430  cv_.notify_one();
431  };
432 
433  // Note this is a trade-off. Adding the callback for every call
434  // is expensive for high frequency calls. For low frequency waits
435  // its more overhead to have the callback being called all the time.
436  // As we expect the use case to be low frequency calls to wait_until
437  // with relative big pauses between the calls, we install it on demand.
438  auto clock_handler = clock_->create_jump_callback(
439  nullptr,
440  post_time_jump_callback,
441  threshold);
442 
443  if (!clock_->ros_time_is_active()) {
444  auto system_time = std::chrono::system_clock::time_point(
445  // Cast because system clock resolution is too big for nanoseconds on some systems
446  std::chrono::duration_cast<std::chrono::system_clock::duration>(
447  std::chrono::nanoseconds(abs_time.nanoseconds())));
448 
449  return cv_.wait_until(lock, system_time, [this, &pred] () {
450  return time_source_changed_ || pred();
451  });
452  }
453 
454  // RCL_ROS_TIME with ros_time_is_active.
455  // Just wait without "until" because installed
456  // jump callbacks wake the cv on every new sample.
457  cv_.wait(lock, [this, &pred, &abs_time] () {
458  return clock_->now() >= abs_time || time_source_changed_ || pred();
459  });
460 
461  return clock_->now() < abs_time;
462  }
463 
464 public:
465  explicit ClockWaiterImpl(const rclcpp::Clock::SharedPtr & clock)
466  :clock_(clock)
467  {
468  }
469 
470  bool
471  wait_until(
472  std::unique_lock<std::mutex> & lock,
473  const rclcpp::Time & abs_time, const std::function<bool ()> & pred)
474  {
475  switch(clock_->get_clock_type()) {
477  throw std::runtime_error("Error, wait on uninitialized clock called");
478  case RCL_ROS_TIME:
479  return wait_until_ros_time(lock, abs_time, pred);
480  break;
481  case RCL_STEADY_TIME:
482  return wait_until_steady_time(lock, abs_time, pred);
483  break;
484  case RCL_SYSTEM_TIME:
485  return wait_until_system_time(lock, abs_time, pred);
486  break;
487  }
488 
489  return false;
490  }
491 
492  void
493  notify_one()
494  {
495  cv_.notify_one();
496  }
497 };
498 
499 ClockWaiter::ClockWaiter(const rclcpp::Clock::SharedPtr & clock)
500 :impl_(std::make_unique<ClockWaiterImpl>(clock))
501 {
502 }
503 
504 ClockWaiter::~ClockWaiter() = default;
505 
506 bool
508  std::unique_lock<std::mutex> & lock,
509  const rclcpp::Time & abs_time, const std::function<bool ()> & pred)
510 {
511  return impl_->wait_until(lock, abs_time, pred);
512 }
513 
514 void
516 {
517  impl_->notify_one();
518 }
519 
521 {
522  std::mutex pred_mutex_;
523  bool shutdown_ = false;
524  rclcpp::Context::SharedPtr context_;
525  rclcpp::OnShutdownCallbackHandle shutdown_cb_handle_;
526  ClockWaiter::UniquePtr clock_;
527 
528 public:
529  Impl(const rclcpp::Clock::SharedPtr & clock, rclcpp::Context::SharedPtr context)
530  :context_(context),
531  clock_(std::make_unique<ClockWaiter>(clock))
532  {
533  if (!context_ || !context_->is_valid()) {
534  throw std::runtime_error("context cannot be slept with because it's invalid");
535  }
536  // Wake this thread if the context is shutdown
537  shutdown_cb_handle_ = context_->add_on_shutdown_callback(
538  [this]() {
539  {
540  std::unique_lock lock(pred_mutex_);
541  shutdown_ = true;
542  }
543  clock_->notify_one();
544  });
545  }
546 
547  ~Impl()
548  {
549  context_->remove_on_shutdown_callback(shutdown_cb_handle_);
550  }
551 
552  bool
553  wait_until(
554  std::unique_lock<std::mutex> & lock, rclcpp::Time until,
555  const std::function<bool ()> & pred)
556  {
557  if(lock.mutex() != &pred_mutex_) {
558  throw std::runtime_error(
559  "ClockConditionalVariable::wait_until: Internal error, given lock does not use"
560  " mutex returned by this->mutex()");
561  }
562 
563  clock_->wait_until(lock, until, [this, &pred] () -> bool {
564  return shutdown_ || pred();
565  });
566  return true;
567  }
568 
569  void
570  notify_one()
571  {
572  clock_->notify_one();
573  }
574 
575  std::mutex &
576  mutex()
577  {
578  return pred_mutex_;
579  }
580 };
581 
582 ClockConditionalVariable::ClockConditionalVariable(
583  const rclcpp::Clock::SharedPtr & clock,
584  rclcpp::Context::SharedPtr context)
585 :impl_(std::make_unique<Impl>(clock, context))
586 {
587 }
588 
589 ClockConditionalVariable::~ClockConditionalVariable() = default;
590 
591 void
593 {
594  impl_->notify_one();
595 }
596 
597 bool
599  std::unique_lock<std::mutex> & lock, rclcpp::Time until,
600  const std::function<bool ()> & pred)
601 {
602  return impl_->wait_until(lock, until, pred);
603 }
604 
605 std::mutex &
607 {
608  return impl_->mutex();
609 }
610 
611 } // namespace rclcpp
#define rcl_get_default_allocator
Return a properly initialized rcl_allocator_t with default values.
Definition: allocator.h:37
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
Definition: allocator.h:31
RCLCPP_PUBLIC void notify_one()
Definition: clock.cpp:592
RCLCPP_PUBLIC std::mutex & mutex()
Definition: clock.cpp:606
RCLCPP_PUBLIC bool wait_until(std::unique_lock< std::mutex > &lock, rclcpp::Time until, const std::function< bool()> &pred)
Definition: clock.cpp:598
RCLCPP_PUBLIC bool wait_until(std::unique_lock< std::mutex > &lock, const rclcpp::Time &abs_time, const std::function< bool()> &pred)
Definition: clock.cpp:507
RCLCPP_PUBLIC void notify_one()
Definition: clock.cpp:515
RCLCPP_PUBLIC rcl_clock_t * get_clock_handle() noexcept
Return the rcl_clock_t clock handle.
Definition: clock.cpp:295
RCLCPP_PUBLIC bool ros_time_is_active()
Definition: clock.cpp:278
RCLCPP_PUBLIC bool wait_until_started(Context::SharedPtr context=contexts::get_global_default_context())
Definition: clock.cpp:222
RCLCPP_PUBLIC Time now() const
Definition: clock.cpp:74
RCLCPP_PUBLIC bool started()
Definition: clock.cpp:213
RCLCPP_PUBLIC JumpHandler::SharedPtr create_jump_callback(JumpHandler::pre_callback_t pre_callback, JumpHandler::post_callback_t post_callback, const rcl_jump_threshold_t &threshold)
Definition: clock.cpp:330
RCLCPP_PUBLIC Clock(rcl_clock_type_t clock_type=RCL_SYSTEM_TIME)
Default c'tor.
Definition: clock.cpp:68
RCLCPP_PUBLIC bool sleep_until(Time until, Context::SharedPtr context=contexts::get_global_default_context())
Definition: clock.cpp:97
RCLCPP_PUBLIC void cancel_sleep_or_wait()
Definition: clock.cpp:87
RCLCPP_PUBLIC std::mutex & get_clock_mutex() noexcept
Get the clock's mutex.
Definition: clock.cpp:307
RCLCPP_PUBLIC bool sleep_for(Duration rel_time, Context::SharedPtr context=contexts::get_global_default_context())
Definition: clock.cpp:207
rcl_duration_value_t nanoseconds() const
Get duration in nanosecods.
Definition: duration.cpp:249
RCLCPP_PUBLIC rcl_time_point_value_t nanoseconds() const
Get the nanoseconds since epoch.
Definition: time.cpp:212
RCLCPP_PUBLIC rcl_clock_type_t get_clock_type() const
Get the clock type.
Definition: time.cpp:224
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
Encapsulation of a time source.
Definition: time.h:138
rcl_duration_value_t nanoseconds
Duration in nanoseconds and its source.
Definition: time.h:77
Describe the prerequisites for calling a time jump callback.
Definition: time.h:114
rcl_duration_t min_forward
Definition: time.h:119
bool on_clock_change
True to call callback when the clock type changes.
Definition: time.h:116
rcl_duration_t min_backward
Definition: time.h:122
Struct to describe a jump in time.
Definition: time.h:95
rcl_clock_change_t clock_change
Indicate whether or not the source of time changed.
Definition: time.h:97
rcl_time_point_value_t nanoseconds
Nanoseconds of the point in time.
Definition: time.h:158
enum rcl_clock_type_e rcl_clock_type_t
Time source type, used to indicate the source of a time measurement.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_clock_get_now(rcl_clock_t *clock, rcl_time_point_value_t *time_point_value)
Fill the time point value with the current value of the associated clock.
Definition: time.c:263
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_clock_fini(rcl_clock_t *clock)
Finalize a clock.
Definition: time.c:132
@ RCL_ROS_TIME_NO_CHANGE
The source before and after the jump is ROS_TIME.
Definition: time.h:84
RCL_PUBLIC RCL_WARN_UNUSED bool rcl_clock_time_started(rcl_clock_t *clock)
Check if the clock has started.
Definition: time.c:76
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_clock_add_jump_callback(rcl_clock_t *clock, rcl_jump_threshold_t threshold, rcl_jump_callback_t callback, void *user_data)
Add a callback to be called when a time jump exceeds a threshold.
Definition: time.c:392
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_is_enabled_ros_time_override(rcl_clock_t *clock, bool *is_enabled)
Check if the RCL_ROS_TIME time source has the override enabled.
Definition: time.c:343
@ RCL_ROS_TIME
Use ROS time.
Definition: time.h:66
@ RCL_SYSTEM_TIME
Use system time.
Definition: time.h:68
@ RCL_CLOCK_UNINITIALIZED
Clock uninitialized.
Definition: time.h:64
@ RCL_STEADY_TIME
Use a steady clock time.
Definition: time.h:70
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_clock_init(rcl_clock_type_t clock_type, rcl_clock_t *clock, rcl_allocator_t *allocator)
Initialize a clock based on the passed type.
Definition: time.c:98
RCL_PUBLIC RCL_WARN_UNUSED bool rcl_clock_valid(rcl_clock_t *clock)
Check if the clock has valid values.
Definition: time.c:86
#define RCL_RET_OK
Success return code.
Definition: types.h:27
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24