ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
ROS 2 C++ Client Library with ROS Client Library
timer.hpp
1 // Copyright 2014 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 #ifndef RCLCPP__TIMER_HPP_
16 #define RCLCPP__TIMER_HPP_
17 
18 #include <atomic>
19 #include <chrono>
20 #include <functional>
21 #include <optional>
22 #include <memory>
23 #include <sstream>
24 #include <thread>
25 #include <type_traits>
26 #include <utility>
27 
28 #include "rclcpp/clock.hpp"
29 #include "rclcpp/context.hpp"
30 #include "rclcpp/function_traits.hpp"
31 #include "rclcpp/macros.hpp"
32 #include "rclcpp/rate.hpp"
33 #include "rclcpp/utilities.hpp"
34 #include "rclcpp/visibility_control.hpp"
35 #include "tracetools/tracetools.h"
36 #include "tracetools/utils.hpp"
37 
38 #include "rcl/error_handling.h"
39 #include "rcl/timer.h"
40 
41 #include "rmw/error_handling.h"
42 #include "rmw/rmw.h"
43 
44 namespace rclcpp
45 {
46 
47 struct TimerInfo
48 {
49  Time expected_call_time;
50  Time actual_call_time;
51 };
52 
53 class TimerBase
54 {
55 public:
56  RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(TimerBase)
57 
58 
68  RCLCPP_PUBLIC
69  explicit TimerBase(
70  Clock::SharedPtr clock,
71  std::chrono::nanoseconds period,
72  rclcpp::Context::SharedPtr context,
73  bool autostart = true);
74 
76  RCLCPP_PUBLIC
77  virtual
78  ~TimerBase();
79 
81 
84  RCLCPP_PUBLIC
85  void
86  cancel();
87 
89 
94  RCLCPP_PUBLIC
95  bool
96  is_canceled();
97 
99 
102  RCLCPP_PUBLIC
103  void
104  reset();
105 
107 
114  RCLCPP_PUBLIC
115  virtual std::shared_ptr<void>
116  call() = 0;
117 
119 
122  RCLCPP_PUBLIC
123  virtual void
124  execute_callback(const std::shared_ptr<void> & data) = 0;
125 
126  RCLCPP_PUBLIC
127  std::shared_ptr<const rcl_timer_t>
128  get_timer_handle();
129 
131 
136  RCLCPP_PUBLIC
137  std::chrono::nanoseconds
139 
141 
142  virtual bool is_steady() = 0;
143 
145 
151  RCLCPP_PUBLIC
152  bool is_ready();
153 
155 
164  RCLCPP_PUBLIC
165  bool
166  exchange_in_use_by_wait_set_state(bool in_use_state);
167 
169 
184  RCLCPP_PUBLIC
185  void
186  set_on_reset_callback(std::function<void(size_t)> callback);
187 
189  RCLCPP_PUBLIC
190  void
192 
193 protected:
194  std::recursive_mutex callback_mutex_;
195  // Declare callback before timer_handle_, so on destruction
196  // the callback is destroyed last. Otherwise, the rcl timer
197  // callback would point briefly to a destroyed function.
198  // Clearing the callback on timer destructor also makes sure
199  // the rcl callback is cleared before on_reset_callback_.
200  std::function<void(size_t)> on_reset_callback_{nullptr};
201 
202  Clock::SharedPtr clock_;
203  std::shared_ptr<rcl_timer_t> timer_handle_;
204 
205  std::atomic<bool> in_use_by_wait_set_{false};
206 
207  RCLCPP_PUBLIC
208  void
209  set_on_reset_callback(rcl_event_callback_t callback, const void * user_data);
210 };
211 
212 using VoidCallbackType = std::function<void ()>;
213 using TimerCallbackType = std::function<void (TimerBase &)>;
214 using TimerInfoCallbackType = std::function<void (const TimerInfo &)>;
215 
217 template<
218  typename FunctorT,
219  typename std::enable_if<
223  >::type * = nullptr
224 >
225 class GenericTimer : public TimerBase
226 {
227 public:
228  RCLCPP_SMART_PTR_DEFINITIONS(GenericTimer)
229 
230 
238  explicit GenericTimer(
239  Clock::SharedPtr clock, std::chrono::nanoseconds period, FunctorT && callback,
240  rclcpp::Context::SharedPtr context, bool autostart = true
241  )
242  : TimerBase(clock, period, context, autostart), callback_(std::forward<FunctorT>(callback))
243  {
244  TRACETOOLS_TRACEPOINT(
245  rclcpp_timer_callback_added,
246  static_cast<const void *>(get_timer_handle().get()),
247  reinterpret_cast<const void *>(&callback_));
248 #ifndef TRACETOOLS_DISABLED
249  if (TRACETOOLS_TRACEPOINT_ENABLED(rclcpp_callback_register)) {
250  char * symbol = tracetools::get_symbol(callback_);
251  TRACETOOLS_DO_TRACEPOINT(
252  rclcpp_callback_register,
253  reinterpret_cast<const void *>(&callback_),
254  symbol);
255  std::free(symbol);
256  }
257 #endif
258  }
259 
261  virtual ~GenericTimer()
262  {
263  // Stop the timer from running.
264  cancel();
265  }
266 
271  std::shared_ptr<void>
272  call() override
273  {
274  auto timer_call_info_ = std::make_shared<rcl_timer_call_info_t>();
275  rcl_ret_t ret = rcl_timer_call_with_info(timer_handle_.get(), timer_call_info_.get());
276  if (ret == RCL_RET_TIMER_CANCELED) {
277  return nullptr;
278  }
279  if (ret != RCL_RET_OK) {
280  throw std::runtime_error("Failed to notify timer that callback occurred");
281  }
282  return timer_call_info_;
283  }
284 
288  void
289  execute_callback(const std::shared_ptr<void> & data) override
290  {
291  TRACETOOLS_TRACEPOINT(callback_start, reinterpret_cast<const void *>(&callback_), false);
292  execute_callback_delegate<>(*static_cast<rcl_timer_call_info_t *>(data.get()));
293  TRACETOOLS_TRACEPOINT(callback_end, reinterpret_cast<const void *>(&callback_));
294  }
295 
296  // void specialization
297  template<
298  typename CallbackT = FunctorT,
299  typename std::enable_if<
301  >::type * = nullptr
302  >
303  void
304  execute_callback_delegate(const rcl_timer_call_info_t &)
305  {
306  callback_();
307  }
308 
309  template<
310  typename CallbackT = FunctorT,
311  typename std::enable_if<
313  >::type * = nullptr
314  >
315  void
316  execute_callback_delegate(const rcl_timer_call_info_t &)
317  {
318  callback_(*this);
319  }
320 
321 
322  template<
323  typename CallbackT = FunctorT,
324  typename std::enable_if<
326  >::type * = nullptr
327  >
328  void
329  execute_callback_delegate(const rcl_timer_call_info_t & timer_call_info)
330  {
331  const TimerInfo info{Time{timer_call_info.expected_call_time, clock_->get_clock_type()},
332  Time{timer_call_info.actual_call_time, clock_->get_clock_type()}};
333  callback_(info);
334  }
335 
337 
338  bool
339  is_steady() override
340  {
341  return clock_->get_clock_type() == RCL_STEADY_TIME;
342  }
343 
344 protected:
345  RCLCPP_DISABLE_COPY(GenericTimer)
346 
347  FunctorT callback_;
348 };
349 
350 template<
351  typename FunctorT,
352  typename std::enable_if<
356  >::type * = nullptr
357 >
358 class WallTimer : public GenericTimer<FunctorT>
359 {
360 public:
361  RCLCPP_SMART_PTR_DEFINITIONS(WallTimer)
362 
363 
371  std::chrono::nanoseconds period,
372  FunctorT && callback,
373  rclcpp::Context::SharedPtr context,
374  bool autostart = true)
375  : GenericTimer<FunctorT>(
376  std::make_shared<Clock>(RCL_STEADY_TIME), period, std::move(callback), context, autostart)
377  {}
378 
379 protected:
380  RCLCPP_DISABLE_COPY(WallTimer)
381 };
382 
383 } // namespace rclcpp
384 
385 #endif // RCLCPP__TIMER_HPP_
Context which encapsulates shared state between nodes and other similar entities.
Definition: context.hpp:76
Generic timer. Periodically executes a user-specified callback.
Definition: timer.hpp:226
bool is_steady() override
Is the clock steady (i.e. is the time between ticks constant?)
Definition: timer.hpp:339
void execute_callback(const std::shared_ptr< void > &data) override
Definition: timer.hpp:289
virtual ~GenericTimer()
Default destructor.
Definition: timer.hpp:261
std::shared_ptr< void > call() override
Definition: timer.hpp:272
virtual RCLCPP_PUBLIC ~TimerBase()
TimerBase destructor.
Definition: timer.cpp:77
RCLCPP_PUBLIC bool is_canceled()
Return the timer cancellation state.
Definition: timer.cpp:92
RCLCPP_PUBLIC void reset()
Reset the timer.
Definition: timer.cpp:103
RCLCPP_PUBLIC void clear_on_reset_callback()
Unset the callback registered for reset timer.
Definition: timer.cpp:202
virtual RCLCPP_PUBLIC void execute_callback(const std::shared_ptr< void > &data)=0
Call the callback function when the timer signal is emitted.
virtual RCLCPP_PUBLIC std::shared_ptr< void > call()=0
Indicate that we're about to execute the callback.
RCLCPP_PUBLIC bool exchange_in_use_by_wait_set_state(bool in_use_state)
Exchange the "in use by wait set" state for this timer.
Definition: timer.cpp:147
virtual bool is_steady()=0
Is the clock steady (i.e. is the time between ticks constant?)
RCLCPP_PUBLIC bool is_ready()
Check if the timer is ready to trigger the callback.
Definition: timer.cpp:116
RCLCPP_PUBLIC TimerBase(Clock::SharedPtr clock, std::chrono::nanoseconds period, rclcpp::Context::SharedPtr context, bool autostart=true)
TimerBase constructor.
Definition: timer.cpp:32
RCLCPP_PUBLIC void set_on_reset_callback(std::function< void(size_t)> callback)
Set a callback to be called when the timer is reset.
Definition: timer.cpp:153
RCLCPP_PUBLIC std::chrono::nanoseconds time_until_trigger()
Check how long the timer has until its next scheduled callback.
Definition: timer.cpp:127
RCLCPP_PUBLIC void cancel()
Cancel the timer.
Definition: timer.cpp:83
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
Structure which encapsulates timer information when called.
Definition: timer.h:56
@ RCL_STEADY_TIME
Use a steady clock time.
Definition: time.h:70
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_timer_call_with_info(rcl_timer_t *timer, rcl_timer_call_info_t *call_info)
Same as rcl_timer_call() except that it also retrieves the actual and expected call time.
Definition: timer.c:269
#define RCL_RET_OK
Success return code.
Definition: types.h:27
#define RCL_RET_TIMER_CANCELED
Given timer was canceled return code.
Definition: types.h:95
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24