1818#include < atomic>
1919#include < chrono>
2020#include < functional>
21+ #include < optional>
2122#include < memory>
2223#include < sstream>
2324#include < thread>
4344namespace rclcpp
4445{
4546
47+ struct TimerInfo
48+ {
49+ Time expected_call_time;
50+ Time actual_call_time;
51+ };
52+
4653class TimerBase
4754{
4855public:
@@ -101,16 +108,19 @@ class TimerBase
101108 * The multithreaded executor takes advantage of this to avoid scheduling
102109 * the callback multiple times.
103110 *
104- * \return `true` if the callback should be executed, `false` if the timer was canceled.
111+ * \return a shared_ptr if the callback should be executed, std::nullopt if the timer was canceled.
105112 */
106113 RCLCPP_PUBLIC
107- virtual bool
114+ virtual std::optional<std::shared_ptr< void >>
108115 call () = 0 ;
109116
110117 // / Call the callback function when the timer signal is emitted.
118+ /* *
119+ * \param[in] data the pointer returned by the call function
120+ */
111121 RCLCPP_PUBLIC
112122 virtual void
113- execute_callback () = 0 ;
123+ execute_callback (const std::shared_ptr< void > & data ) = 0 ;
114124
115125 RCLCPP_PUBLIC
116126 std::shared_ptr<const rcl_timer_t >
@@ -198,12 +208,6 @@ class TimerBase
198208 set_on_reset_callback (rcl_event_callback_t callback, const void * user_data);
199209};
200210
201- struct TimerInfo
202- {
203- Time expected_call_time;
204- Time actual_call_time;
205- };
206-
207211using VoidCallbackType = std::function<void ()>;
208212using TimerCallbackType = std::function<void (TimerBase &)>;
209213using TimerInfoCallbackType = std::function<void (const TimerInfo &)>;
@@ -263,27 +267,28 @@ class GenericTimer : public TimerBase
263267 * \sa rclcpp::TimerBase::call
264268 * \throws std::runtime_error if it failed to notify timer that callback will occurr
265269 */
266- bool
270+ std::optional<std::shared_ptr< void >>
267271 call () override
268272 {
273+ rcl_timer_call_info_t timer_call_info_;
269274 rcl_ret_t ret = rcl_timer_call_with_info (timer_handle_.get (), &timer_call_info_);
270275 if (ret == RCL_RET_TIMER_CANCELED) {
271- return false ;
276+ return std:: nullopt ;
272277 }
273278 if (ret != RCL_RET_OK) {
274279 throw std::runtime_error (" Failed to notify timer that callback occurred" );
275280 }
276- return true ;
281+ return std::make_shared< rcl_timer_call_info_t >(timer_call_info_) ;
277282 }
278283
279284 /* *
280285 * \sa rclcpp::TimerBase::execute_callback
281286 */
282287 void
283- execute_callback () override
288+ execute_callback (const std::shared_ptr< void > & data ) override
284289 {
285290 TRACETOOLS_TRACEPOINT (callback_start, reinterpret_cast <const void *>(&callback_), false );
286- execute_callback_delegate<>();
291+ execute_callback_delegate<>(* static_cast < rcl_timer_call_info_t *>(data. get ()) );
287292 TRACETOOLS_TRACEPOINT (callback_end, reinterpret_cast <const void *>(&callback_));
288293 }
289294
@@ -295,7 +300,7 @@ class GenericTimer : public TimerBase
295300 >::type * = nullptr
296301 >
297302 void
298- execute_callback_delegate ()
303+ execute_callback_delegate (const rcl_timer_call_info_t & )
299304 {
300305 callback_ ();
301306 }
@@ -307,7 +312,7 @@ class GenericTimer : public TimerBase
307312 >::type * = nullptr
308313 >
309314 void
310- execute_callback_delegate ()
315+ execute_callback_delegate (const rcl_timer_call_info_t & )
311316 {
312317 callback_ (*this );
313318 }
@@ -320,7 +325,7 @@ class GenericTimer : public TimerBase
320325 >::type * = nullptr
321326 >
322327 void
323- execute_callback_delegate ()
328+ execute_callback_delegate (const rcl_timer_call_info_t & timer_call_info_ )
324329 {
325330 const TimerInfo info{Time{timer_call_info_.expected_call_time , clock_->get_clock_type ()},
326331 Time{timer_call_info_.actual_call_time , clock_->get_clock_type ()}};
@@ -339,14 +344,14 @@ class GenericTimer : public TimerBase
339344 RCLCPP_DISABLE_COPY (GenericTimer)
340345
341346 FunctorT callback_;
342- rcl_timer_call_info_t timer_call_info_;
343347};
344348
345349template <
346350 typename FunctorT,
347351 typename std::enable_if<
348352 rclcpp::function_traits::same_arguments<FunctorT, VoidCallbackType>::value ||
349- rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value
353+ rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value ||
354+ rclcpp::function_traits::same_arguments<FunctorT, TimerInfoCallbackType>::value
350355 >::type * = nullptr
351356>
352357class WallTimer : public GenericTimer <FunctorT>
0 commit comments