Skip to content

Commit 634cb87

Browse files
jmachowinskiatsogiasJanosch Machowinski
authored
Added optional TimerInfo to timer callback (#2343)
Signed-off-by: Alexis Tsogias <[email protected]> Signed-off-by: Janosch Machowinski <[email protected]> Co-authored-by: Alexis Tsogias <[email protected]> Co-authored-by: Janosch Machowinski <[email protected]>
1 parent ddc8a9c commit 634cb87

File tree

12 files changed

+126
-45
lines changed

12 files changed

+126
-45
lines changed

rclcpp/include/rclcpp/executor.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -487,7 +487,7 @@ class Executor
487487
*/
488488
RCLCPP_PUBLIC
489489
static void
490-
execute_timer(rclcpp::TimerBase::SharedPtr timer);
490+
execute_timer(rclcpp::TimerBase::SharedPtr timer, const std::shared_ptr<void> & dataPtr);
491491

492492
/// Run service server executable.
493493
/**

rclcpp/include/rclcpp/experimental/executors/events_executor/events_executor_event_types.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef RCLCPP__EXPERIMENTAL__EXECUTORS__EVENTS_EXECUTOR__EVENTS_EXECUTOR_EVENT_TYPES_HPP_
1616
#define RCLCPP__EXPERIMENTAL__EXECUTORS__EVENTS_EXECUTOR__EVENTS_EXECUTOR_EVENT_TYPES_HPP_
1717

18+
#include <memory>
19+
1820
namespace rclcpp
1921
{
2022
namespace experimental
@@ -34,6 +36,7 @@ enum ExecutorEventType
3436
struct ExecutorEvent
3537
{
3638
const void * entity_key;
39+
std::shared_ptr<void> data;
3740
int waitable_data;
3841
ExecutorEventType type;
3942
size_t num_events;

rclcpp/include/rclcpp/experimental/timers_manager.hpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,8 @@ class TimersManager
8686
RCLCPP_PUBLIC
8787
TimersManager(
8888
std::shared_ptr<rclcpp::Context> context,
89-
std::function<void(const rclcpp::TimerBase *)> on_ready_callback = nullptr);
89+
std::function<void(const rclcpp::TimerBase *,
90+
const std::shared_ptr<void> &)> on_ready_callback = nullptr);
9091

9192
/**
9293
* @brief Destruct the TimersManager object making sure to stop thread and release memory.
@@ -164,9 +165,10 @@ class TimersManager
164165
* the TimersManager on_ready_callback was passed during construction.
165166
*
166167
* @param timer_id the timer ID of the timer to execute
168+
* @param data internal data of the timer
167169
*/
168170
RCLCPP_PUBLIC
169-
void execute_ready_timer(const rclcpp::TimerBase * timer_id);
171+
void execute_ready_timer(const rclcpp::TimerBase * timer_id, const std::shared_ptr<void> & data);
170172

171173
/**
172174
* @brief Get the amount of time before the next timer triggers.
@@ -529,7 +531,8 @@ class TimersManager
529531
void execute_ready_timers_unsafe();
530532

531533
// Callback to be called when timer is ready
532-
std::function<void(const rclcpp::TimerBase *)> on_ready_callback_;
534+
std::function<void(const rclcpp::TimerBase *,
535+
const std::shared_ptr<void> &)> on_ready_callback_ = nullptr;
533536

534537
// Thread used to run the timers execution task
535538
std::thread timers_thread_;

rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -370,7 +370,8 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
370370
++it;
371371
continue;
372372
}
373-
if (!timer->call()) {
373+
auto data = timer->call();
374+
if (!data) {
374375
// timer was cancelled, skip it.
375376
++it;
376377
continue;
@@ -379,6 +380,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
379380
any_exec.timer = timer;
380381
any_exec.callback_group = group;
381382
any_exec.node_base = get_node_by_group(group, weak_groups_to_nodes);
383+
any_exec.data = data;
382384
timer_handles_.erase(it);
383385
return;
384386
}

rclcpp/include/rclcpp/timer.hpp

Lines changed: 43 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <atomic>
1919
#include <chrono>
2020
#include <functional>
21+
#include <optional>
2122
#include <memory>
2223
#include <sstream>
2324
#include <thread>
@@ -43,6 +44,12 @@
4344
namespace rclcpp
4445
{
4546

47+
struct TimerInfo
48+
{
49+
Time expected_call_time;
50+
Time actual_call_time;
51+
};
52+
4653
class TimerBase
4754
{
4855
public:
@@ -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,16 +209,17 @@ class TimerBase
198209
set_on_reset_callback(rcl_event_callback_t callback, const void * user_data);
199210
};
200211

201-
202212
using VoidCallbackType = std::function<void ()>;
203213
using TimerCallbackType = std::function<void (TimerBase &)>;
214+
using TimerInfoCallbackType = std::function<void (const TimerInfo &)>;
204215

205216
/// Generic timer. Periodically executes a user-specified callback.
206217
template<
207218
typename FunctorT,
208219
typename std::enable_if<
209220
rclcpp::function_traits::same_arguments<FunctorT, VoidCallbackType>::value ||
210-
rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value
221+
rclcpp::function_traits::same_arguments<FunctorT, TimerCallbackType>::value ||
222+
rclcpp::function_traits::same_arguments<FunctorT, TimerInfoCallbackType>::value
211223
>::type * = nullptr
212224
>
213225
class GenericTimer : public TimerBase
@@ -256,27 +268,28 @@ class GenericTimer : public TimerBase
256268
* \sa rclcpp::TimerBase::call
257269
* \throws std::runtime_error if it failed to notify timer that callback will occurr
258270
*/
259-
bool
271+
std::shared_ptr<void>
260272
call() override
261273
{
262-
rcl_ret_t ret = rcl_timer_call(timer_handle_.get());
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());
263276
if (ret == RCL_RET_TIMER_CANCELED) {
264-
return false;
277+
return nullptr;
265278
}
266279
if (ret != RCL_RET_OK) {
267280
throw std::runtime_error("Failed to notify timer that callback occurred");
268281
}
269-
return true;
282+
return timer_call_info_;
270283
}
271284

272285
/**
273286
* \sa rclcpp::TimerBase::execute_callback
274287
*/
275288
void
276-
execute_callback() override
289+
execute_callback(const std::shared_ptr<void> & data) override
277290
{
278291
TRACETOOLS_TRACEPOINT(callback_start, reinterpret_cast<const void *>(&callback_), false);
279-
execute_callback_delegate<>();
292+
execute_callback_delegate<>(*static_cast<rcl_timer_call_info_t *>(data.get()));
280293
TRACETOOLS_TRACEPOINT(callback_end, reinterpret_cast<const void *>(&callback_));
281294
}
282295

@@ -288,7 +301,7 @@ class GenericTimer : public TimerBase
288301
>::type * = nullptr
289302
>
290303
void
291-
execute_callback_delegate()
304+
execute_callback_delegate(const rcl_timer_call_info_t &)
292305
{
293306
callback_();
294307
}
@@ -300,11 +313,26 @@ class GenericTimer : public TimerBase
300313
>::type * = nullptr
301314
>
302315
void
303-
execute_callback_delegate()
316+
execute_callback_delegate(const rcl_timer_call_info_t &)
304317
{
305318
callback_(*this);
306319
}
307320

321+
322+
template<
323+
typename CallbackT = FunctorT,
324+
typename std::enable_if<
325+
rclcpp::function_traits::same_arguments<CallbackT, TimerInfoCallbackType>::value
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+
308336
/// Is the clock steady (i.e. is the time between ticks constant?)
309337
/** \return True if the clock used by this timer is steady. */
310338
bool
@@ -323,7 +351,8 @@ template<
323351
typename FunctorT,
324352
typename std::enable_if<
325353
rclcpp::function_traits::same_arguments<FunctorT, VoidCallbackType>::value ||
326-
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
327356
>::type * = nullptr
328357
>
329358
class WallTimer : public GenericTimer<FunctorT>

rclcpp/src/rclcpp/executor.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -383,7 +383,7 @@ Executor::execute_any_executable(AnyExecutable & any_exec)
383383
TRACETOOLS_TRACEPOINT(
384384
rclcpp_executor_execute,
385385
static_cast<const void *>(any_exec.timer->get_timer_handle().get()));
386-
execute_timer(any_exec.timer);
386+
execute_timer(any_exec.timer, any_exec.data);
387387
}
388388
if (any_exec.subscription) {
389389
TRACETOOLS_TRACEPOINT(
@@ -547,9 +547,9 @@ Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr subscription)
547547
}
548548

549549
void
550-
Executor::execute_timer(rclcpp::TimerBase::SharedPtr timer)
550+
Executor::execute_timer(rclcpp::TimerBase::SharedPtr timer, const std::shared_ptr<void> & dataPtr)
551551
{
552-
timer->execute_callback();
552+
timer->execute_callback(dataPtr);
553553
}
554554

555555
void
@@ -690,6 +690,7 @@ Executor::get_next_ready_executable(AnyExecutable & any_executable)
690690
if (entity_iter != current_collection_.timers.end()) {
691691
auto callback_group = entity_iter->second.callback_group.lock();
692692
if (callback_group && !callback_group->can_be_taken_from()) {
693+
current_timer_index++;
693694
continue;
694695
}
695696
// At this point the timer is either ready for execution or was perhaps
@@ -698,14 +699,17 @@ Executor::get_next_ready_executable(AnyExecutable & any_executable)
698699
// it from the wait result.
699700
wait_result_->clear_timer_with_index(current_timer_index);
700701
// Check that the timer should be called still, i.e. it wasn't canceled.
701-
if (!timer->call()) {
702+
any_executable.data = timer->call();
703+
if (!any_executable.data) {
704+
current_timer_index++;
702705
continue;
703706
}
704707
any_executable.timer = timer;
705708
any_executable.callback_group = callback_group;
706709
valid_executable = true;
707710
break;
708711
}
712+
current_timer_index++;
709713
}
710714
}
711715

rclcpp/src/rclcpp/executors/static_single_threaded_executor.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -154,11 +154,15 @@ bool StaticSingleThreadedExecutor::execute_ready_executables(
154154
auto entity_iter = collection.timers.find(timer->get_timer_handle().get());
155155
if (entity_iter != collection.timers.end()) {
156156
wait_result.clear_timer_with_index(current_timer_index);
157-
if (timer->call()) {
158-
execute_timer(timer);
159-
any_ready_executable = true;
160-
if (spin_once) {return any_ready_executable;}
157+
auto data = timer->call();
158+
if (!data) {
159+
// someone canceled the timer between is_ready and call
160+
continue;
161161
}
162+
163+
execute_timer(std::move(timer), data);
164+
any_ready_executable = true;
165+
if (spin_once) {return any_ready_executable;}
162166
}
163167
}
164168

rclcpp/src/rclcpp/experimental/executors/events_executor/events_executor.cpp

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -40,10 +40,12 @@ EventsExecutor::EventsExecutor(
4040
// The timers manager can be used either to only track timers (in this case an expired
4141
// timer will generate an executor event and then it will be executed by the executor thread)
4242
// or it can also take care of executing expired timers in its dedicated thread.
43-
std::function<void(const rclcpp::TimerBase *)> timer_on_ready_cb = nullptr;
43+
std::function<void(const rclcpp::TimerBase *,
44+
const std::shared_ptr<void> &)> timer_on_ready_cb = nullptr;
4445
if (!execute_timers_separate_thread) {
45-
timer_on_ready_cb = [this](const rclcpp::TimerBase * timer_id) {
46-
ExecutorEvent event = {timer_id, -1, ExecutorEventType::TIMER_EVENT, 1};
46+
timer_on_ready_cb =
47+
[this](const rclcpp::TimerBase * timer_id, const std::shared_ptr<void> & data) {
48+
ExecutorEvent event = {timer_id, data, -1, ExecutorEventType::TIMER_EVENT, 1};
4749
this->events_queue_->enqueue(event);
4850
};
4951
}
@@ -88,7 +90,7 @@ EventsExecutor::EventsExecutor(
8890
}
8991

9092
ExecutorEvent event =
91-
{notify_waitable_entity_id, waitable_data, ExecutorEventType::WAITABLE_EVENT, 1};
93+
{notify_waitable_entity_id, nullptr, waitable_data, ExecutorEventType::WAITABLE_EVENT, 1};
9294
this->events_queue_->enqueue(event);
9395
});
9496

@@ -325,7 +327,7 @@ EventsExecutor::execute_event(const ExecutorEvent & event)
325327
case ExecutorEventType::TIMER_EVENT:
326328
{
327329
timers_manager_->execute_ready_timer(
328-
static_cast<const rclcpp::TimerBase *>(event.entity_key));
330+
static_cast<const rclcpp::TimerBase *>(event.entity_key), event.data);
329331
break;
330332
}
331333
case ExecutorEventType::WAITABLE_EVENT:
@@ -485,7 +487,7 @@ EventsExecutor::create_entity_callback(
485487
{
486488
std::function<void(size_t)>
487489
callback = [this, entity_key, event_type](size_t num_events) {
488-
ExecutorEvent event = {entity_key, -1, event_type, num_events};
490+
ExecutorEvent event = {entity_key, nullptr, -1, event_type, num_events};
489491
this->events_queue_->enqueue(event);
490492
};
491493
return callback;
@@ -497,7 +499,7 @@ EventsExecutor::create_waitable_callback(const rclcpp::Waitable * entity_key)
497499
std::function<void(size_t, int)>
498500
callback = [this, entity_key](size_t num_events, int waitable_data) {
499501
ExecutorEvent event =
500-
{entity_key, waitable_data, ExecutorEventType::WAITABLE_EVENT, num_events};
502+
{entity_key, nullptr, waitable_data, ExecutorEventType::WAITABLE_EVENT, num_events};
501503
this->events_queue_->enqueue(event);
502504
};
503505
return callback;

0 commit comments

Comments
 (0)