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,20 @@ 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 valid shared_ptr if the callback should be executed,
112+ * an invalid shared_ptr (nullptr) if the timer was canceled.
105113 */
106114 RCLCPP_PUBLIC
107- virtual bool
115+ virtual std::shared_ptr< void >
108116 call () = 0 ;
109117
110118 // / Call the callback function when the timer signal is emitted.
119+ /* *
120+ * \param[in] data the pointer returned by the call function
121+ */
111122 RCLCPP_PUBLIC
112123 virtual void
113- execute_callback () = 0 ;
124+ execute_callback (const std::shared_ptr< void > & data ) = 0 ;
114125
115126 RCLCPP_PUBLIC
116127 std::shared_ptr<const rcl_timer_t >
@@ -198,12 +209,6 @@ class TimerBase
198209 set_on_reset_callback (rcl_event_callback_t callback, const void * user_data);
199210};
200211
201- struct TimerInfo
202- {
203- Time expected_call_time;
204- Time actual_call_time;
205- };
206-
207212using VoidCallbackType = std::function<void ()>;
208213using TimerCallbackType = std::function<void (TimerBase &)>;
209214using TimerInfoCallbackType = std::function<void (const TimerInfo &)>;
@@ -263,27 +268,28 @@ class GenericTimer : public TimerBase
263268 * \sa rclcpp::TimerBase::call
264269 * \throws std::runtime_error if it failed to notify timer that callback will occurr
265270 */
266- bool
271+ std::shared_ptr< void >
267272 call () override
268273 {
274+ rcl_timer_call_info_t timer_call_info_;
269275 rcl_ret_t ret = rcl_timer_call_with_info (timer_handle_.get (), &timer_call_info_);
270276 if (ret == RCL_RET_TIMER_CANCELED) {
271- return false ;
277+ return nullptr ;
272278 }
273279 if (ret != RCL_RET_OK) {
274280 throw std::runtime_error (" Failed to notify timer that callback occurred" );
275281 }
276- return true ;
282+ return std::make_shared< rcl_timer_call_info_t >(timer_call_info_) ;
277283 }
278284
279285 /* *
280286 * \sa rclcpp::TimerBase::execute_callback
281287 */
282288 void
283- execute_callback () override
289+ execute_callback (const std::shared_ptr< void > & data ) override
284290 {
285291 TRACETOOLS_TRACEPOINT (callback_start, reinterpret_cast <const void *>(&callback_), false );
286- execute_callback_delegate<>();
292+ execute_callback_delegate<>(* static_cast < rcl_timer_call_info_t *>(data. get ()) );
287293 TRACETOOLS_TRACEPOINT (callback_end, reinterpret_cast <const void *>(&callback_));
288294 }
289295
@@ -295,7 +301,7 @@ class GenericTimer : public TimerBase
295301 >::type * = nullptr
296302 >
297303 void
298- execute_callback_delegate ()
304+ execute_callback_delegate (const rcl_timer_call_info_t & )
299305 {
300306 callback_ ();
301307 }
@@ -307,7 +313,7 @@ class GenericTimer : public TimerBase
307313 >::type * = nullptr
308314 >
309315 void
310- execute_callback_delegate ()
316+ execute_callback_delegate (const rcl_timer_call_info_t & )
311317 {
312318 callback_ (*this );
313319 }
@@ -320,7 +326,7 @@ class GenericTimer : public TimerBase
320326 >::type * = nullptr
321327 >
322328 void
323- execute_callback_delegate ()
329+ execute_callback_delegate (const rcl_timer_call_info_t & timer_call_info_ )
324330 {
325331 const TimerInfo info{Time{timer_call_info_.expected_call_time , clock_->get_clock_type ()},
326332 Time{timer_call_info_.actual_call_time , clock_->get_clock_type ()}};
@@ -339,14 +345,14 @@ class GenericTimer : public TimerBase
339345 RCLCPP_DISABLE_COPY (GenericTimer)
340346
341347 FunctorT callback_;
342- rcl_timer_call_info_t timer_call_info_;
343348};
344349
345350template <
346351 typename FunctorT,
347352 typename std::enable_if<
348353 rclcpp::function_traits::same_arguments<FunctorT, VoidCallbackType>::value ||
349- rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value
354+ rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value ||
355+ rclcpp::function_traits::same_arguments<FunctorT, TimerInfoCallbackType>::value
350356 >::type * = nullptr
351357>
352358class WallTimer : public GenericTimer <FunctorT>
0 commit comments