Skip to content

Commit

Permalink
Fix race condition in TimeSource clock thread setup (#1623)
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic committed Apr 7, 2021
1 parent 98fc7fe commit 41fedb7
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -261,9 +261,9 @@ void TimeSource::create_clock_sub()
clock_executor_ =
std::make_shared<rclcpp::executors::SingleThreadedExecutor>(exec_options);
if (!clock_executor_thread_.joinable()) {
cancel_clock_executor_promise_ = std::promise<void>{};
clock_executor_thread_ = std::thread(
[this]() {
cancel_clock_executor_promise_ = std::promise<void>{};
auto future = cancel_clock_executor_promise_.get_future();
clock_executor_->add_callback_group(clock_callback_group_, node_base_);
clock_executor_->spin_until_future_complete(future);
Expand Down

0 comments on commit 41fedb7

Please sign in to comment.