Skip to content

Commit

Permalink
style
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Mar 26, 2024
1 parent 2a88295 commit 245bb50
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
7 changes: 4 additions & 3 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,10 @@ Executor::Executor(const rclcpp::ExecutorOptions & options)
}
});

notify_waitable_->set_on_ready_callback([this](auto, auto) {
this->entities_need_rebuild_.store(true);
});
notify_waitable_->set_on_ready_callback(
[this](auto, auto) {
this->entities_need_rebuild_.store(true);
});

notify_waitable_->add_guard_condition(interrupt_guard_condition_);
notify_waitable_->add_guard_condition(shutdown_guard_condition_);
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/test/rclcpp/test_add_callback_groups_to_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,8 @@ TYPED_TEST(TestAddCallbackGroupsToExecutor, add_callback_groups_after_add_node_t

auto count_callback_groups_in_node = [](auto node) {
size_t num = 0;
node->get_node_base_interface()->for_each_callback_group([&num](auto) {
node->get_node_base_interface()->for_each_callback_group(
[&num](auto) {
num++;
});
return num;
Expand Down

0 comments on commit 245bb50

Please sign in to comment.