Skip to content

Commit e920e72

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
fix: Make passing of timer data thread safe
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent 89056f6 commit e920e72

File tree

12 files changed

+105
-50
lines changed

12 files changed

+105
-50
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
@@ -368,7 +368,8 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
368368
++it;
369369
continue;
370370
}
371-
if (!timer->call()) {
371+
auto data = timer->call();
372+
if (!data) {
372373
// timer was cancelled, skip it.
373374
++it;
374375
continue;
@@ -377,6 +378,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
377378
any_exec.timer = timer;
378379
any_exec.callback_group = group;
379380
any_exec.node_base = get_node_by_group(group, weak_groups_to_nodes);
381+
any_exec.data = data;
380382
timer_handles_.erase(it);
381383
return;
382384
}

rclcpp/include/rclcpp/timer.hpp

Lines changed: 25 additions & 19 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,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-
207212
using VoidCallbackType = std::function<void ()>;
208213
using TimerCallbackType = std::function<void (TimerBase &)>;
209214
using 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

345350
template<
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
>
352358
class WallTimer : public GenericTimer<FunctorT>

rclcpp/src/rclcpp/executor.cpp

Lines changed: 5 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
@@ -698,7 +698,8 @@ Executor::get_next_ready_executable(AnyExecutable & any_executable)
698698
// it from the wait result.
699699
wait_result_->clear_timer_with_index(current_timer_index);
700700
// Check that the timer should be called still, i.e. it wasn't canceled.
701-
if (!timer->call()) {
701+
any_executable.data = timer->call();
702+
if (!any_executable.data) {
702703
continue;
703704
}
704705
any_executable.timer = timer;

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;

rclcpp/src/rclcpp/experimental/timers_manager.cpp

Lines changed: 20 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ using rclcpp::experimental::TimersManager;
2727

2828
TimersManager::TimersManager(
2929
std::shared_ptr<rclcpp::Context> context,
30-
std::function<void(const rclcpp::TimerBase *)> on_ready_callback)
30+
std::function<void(const rclcpp::TimerBase *, const std::shared_ptr<void> &)> on_ready_callback)
3131
: on_ready_callback_(on_ready_callback),
3232
context_(context)
3333
{
@@ -148,24 +148,30 @@ bool TimersManager::execute_head_timer()
148148
if (timer_ready) {
149149
// NOTE: here we always execute the timer, regardless of whether the
150150
// on_ready_callback is set or not.
151-
head_timer->call();
152-
head_timer->execute_callback();
151+
auto data = head_timer->call();
152+
if (!data) {
153+
// someone canceled the timer between is_ready and call
154+
return false;
155+
}
156+
head_timer->execute_callback(data);
153157
timers_heap.heapify_root();
154158
weak_timers_heap_.store(timers_heap);
155159
}
156160

157161
return timer_ready;
158162
}
159163

160-
void TimersManager::execute_ready_timer(const rclcpp::TimerBase * timer_id)
164+
void TimersManager::execute_ready_timer(
165+
const rclcpp::TimerBase * timer_id,
166+
const std::shared_ptr<void> & data)
161167
{
162168
TimerPtr ready_timer;
163169
{
164170
std::unique_lock<std::mutex> lock(timers_mutex_);
165171
ready_timer = weak_timers_heap_.get_timer(timer_id);
166172
}
167173
if (ready_timer) {
168-
ready_timer->execute_callback();
174+
ready_timer->execute_callback(data);
169175
}
170176
}
171177

@@ -215,11 +221,16 @@ void TimersManager::execute_ready_timers_unsafe()
215221
const size_t number_ready_timers = locked_heap.get_number_ready_timers();
216222
size_t executed_timers = 0;
217223
while (executed_timers < number_ready_timers && head_timer->is_ready()) {
218-
head_timer->call();
219-
if (on_ready_callback_) {
220-
on_ready_callback_(head_timer.get());
224+
auto data = head_timer->call();
225+
if (data) {
226+
if (on_ready_callback_) {
227+
on_ready_callback_(head_timer.get(), data);
228+
} else {
229+
head_timer->execute_callback(data);
230+
}
221231
} else {
222-
head_timer->execute_callback();
232+
// someone canceled the timer between is_ready and call
233+
// we don't do anything, as the timer is now 'processed'
223234
}
224235

225236
executed_timers++;

rclcpp/test/rclcpp/executors/test_events_queue.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -68,6 +68,7 @@ TEST(TestEventsQueue, SimpleQueueTest)
6868
// Lets push an event into the queue and get it back
6969
rclcpp::experimental::executors::ExecutorEvent push_event = {
7070
simple_queue.get(),
71+
nullptr,
7172
99,
7273
rclcpp::experimental::executors::ExecutorEventType::SUBSCRIPTION_EVENT,
7374
1};

0 commit comments

Comments
 (0)