2525
2626#include " rclcpp/exceptions.hpp"
2727#include " rclcpp/executor.hpp"
28+ #include " rclcpp/guard_condition.hpp"
2829#include " rclcpp/memory_strategy.hpp"
2930#include " rclcpp/node.hpp"
3031#include " rclcpp/scope_exit.hpp"
@@ -40,55 +41,9 @@ using rclcpp::Executor;
4041using rclcpp::ExecutorOptions;
4142using rclcpp::FutureReturnCode;
4243
43- namespace
44- {
45-
46- std::shared_ptr<rcl_guard_condition_t >
47- create_shutdown_guard_condition (std::shared_ptr<rclcpp::Context> context)
48- {
49- auto custom_deleter = [](rcl_guard_condition_t * guard_condition) {
50- rcl_ret_t ret = rcl_guard_condition_fini (guard_condition);
51- if (RCL_RET_OK != ret) {
52- RCLCPP_ERROR (
53- rclcpp::get_logger (" rclcpp" ),
54- " Failed to finalize shutdown_guard_condition, leaking memory!" );
55- }
56- };
57-
58- auto shutdown_guard_condition =
59- std::shared_ptr<rcl_guard_condition_t >(new rcl_guard_condition_t , custom_deleter);
60- *shutdown_guard_condition = rcl_get_zero_initialized_guard_condition ();
61-
62- rcl_ret_t ret = rcl_guard_condition_init (
63- shutdown_guard_condition.get (),
64- context->get_rcl_context ().get (),
65- rcl_guard_condition_get_default_options ());
66- if (RCL_RET_OK != ret) {
67- throw_from_rcl_error (ret, " failed to create shutdown guard condition" );
68- }
69-
70- context->on_shutdown (
71- [weak_shutdown_guard_condition =
72- std::weak_ptr<rcl_guard_condition_t >(shutdown_guard_condition)]()
73- {
74- auto shared_guard_condition = weak_shutdown_guard_condition.lock ();
75- if (nullptr != shared_guard_condition) {
76- rcl_ret_t status = rcl_trigger_guard_condition (shared_guard_condition.get ());
77- if (status != RCL_RET_OK) {
78- RCUTILS_LOG_ERROR_NAMED (
79- " rclcpp" ,
80- " failed to trigger guard condition in Context shutdown callback(): %s" ,
81- rcl_get_error_string ().str );
82- }
83- }
84- });
85- return shutdown_guard_condition;
86- }
87-
88- } // namespace
89-
9044Executor::Executor (const rclcpp::ExecutorOptions & options)
9145: spinning(false ),
46+ shutdown_guard_condition_(std::make_shared<rclcpp::GuardCondition>(options.context)),
9247 memory_strategy_(options.memory_strategy)
9348{
9449 // Store the context for later use.
@@ -101,14 +56,17 @@ Executor::Executor(const rclcpp::ExecutorOptions & options)
10156 throw_from_rcl_error (ret, " Failed to create interrupt guard condition in Executor constructor" );
10257 }
10358
104- // Register a shutdown hook for the executor with context
105- shutdown_guard_condition_ = create_shutdown_guard_condition (context_);
59+ context_->on_shutdown (
60+ [weak_gc = std::weak_ptr<rclcpp::GuardCondition>{shutdown_guard_condition_}]() {
61+ auto strong_gc = weak_gc.lock ();
62+ if (strong_gc) {
63+ strong_gc->trigger ();
64+ }
65+ });
10666
10767 // The number of guard conditions is always at least 2: 1 for the ctrl-c guard cond,
10868 // and one for the executor's guard cond (interrupt_guard_condition_)
109-
110- // Put the global ctrl-c guard condition in
111- memory_strategy_->add_guard_condition (shutdown_guard_condition_.get ());
69+ memory_strategy_->add_guard_condition (&shutdown_guard_condition_->get_rcl_guard_condition ());
11270
11371 // Put the executor's guard condition in
11472 memory_strategy_->add_guard_condition (&interrupt_guard_condition_);
@@ -179,7 +137,7 @@ Executor::~Executor()
179137 rcl_reset_error ();
180138 }
181139 // Remove and release the sigint guard condition
182- memory_strategy_->remove_guard_condition (shutdown_guard_condition_. get ());
140+ memory_strategy_->remove_guard_condition (& shutdown_guard_condition_-> get_rcl_guard_condition ());
183141}
184142
185143std::vector<rclcpp::CallbackGroup::WeakPtr>
0 commit comments