|
35 | 35 |
|
36 | 36 | #include "./logging_mutex.hpp" |
37 | 37 |
|
38 | | -/// Mutex to protect initialized contexts. |
39 | | -static std::mutex g_contexts_mutex; |
40 | | -/// Weak list of context to be shutdown by the signal handler. |
41 | | -static std::vector<std::weak_ptr<rclcpp::Context>> g_contexts; |
| 38 | +using rclcpp::Context; |
| 39 | + |
| 40 | +namespace rclcpp |
| 41 | +{ |
| 42 | +/// Class to manage vector of weak pointers to all created contexts |
| 43 | +class WeakContextsWrapper |
| 44 | +{ |
| 45 | +public: |
| 46 | + RCLCPP_SMART_PTR_DEFINITIONS(WeakContextsWrapper) |
| 47 | + |
| 48 | + void |
| 49 | + add_context(const Context::SharedPtr & context) |
| 50 | + { |
| 51 | + std::lock_guard<std::mutex> guard(mutex_); |
| 52 | + weak_contexts_.push_back(context); |
| 53 | + } |
| 54 | + |
| 55 | + void |
| 56 | + remove_context(const Context * context) |
| 57 | + { |
| 58 | + std::lock_guard<std::mutex> guard(mutex_); |
| 59 | + weak_contexts_.erase( |
| 60 | + std::remove_if( |
| 61 | + weak_contexts_.begin(), |
| 62 | + weak_contexts_.end(), |
| 63 | + [context](const Context::WeakPtr weak_context) { |
| 64 | + auto locked_context = weak_context.lock(); |
| 65 | + if (!locked_context) { |
| 66 | + // take advantage and removed expired contexts |
| 67 | + return true; |
| 68 | + } |
| 69 | + return locked_context.get() == context; |
| 70 | + } |
| 71 | + ), |
| 72 | + weak_contexts_.end()); |
| 73 | + } |
| 74 | + |
| 75 | + std::vector<Context::SharedPtr> |
| 76 | + get_contexts() |
| 77 | + { |
| 78 | + std::lock_guard<std::mutex> lock(mutex_); |
| 79 | + std::vector<Context::SharedPtr> shared_contexts; |
| 80 | + for (auto it = weak_contexts_.begin(); it != weak_contexts_.end(); /* noop */) { |
| 81 | + auto context_ptr = it->lock(); |
| 82 | + if (!context_ptr) { |
| 83 | + // remove invalid weak context pointers |
| 84 | + it = weak_contexts_.erase(it); |
| 85 | + } else { |
| 86 | + ++it; |
| 87 | + shared_contexts.push_back(context_ptr); |
| 88 | + } |
| 89 | + } |
| 90 | + return shared_contexts; |
| 91 | + } |
| 92 | + |
| 93 | +private: |
| 94 | + std::vector<std::weak_ptr<rclcpp::Context>> weak_contexts_; |
| 95 | + std::mutex mutex_; |
| 96 | +}; |
| 97 | +} // namespace rclcpp |
| 98 | + |
| 99 | +using rclcpp::WeakContextsWrapper; |
| 100 | + |
| 101 | +/// Global vector of weak pointers to all contexts |
| 102 | +static |
| 103 | +WeakContextsWrapper::SharedPtr |
| 104 | +get_weak_contexts() |
| 105 | +{ |
| 106 | + static WeakContextsWrapper::SharedPtr weak_contexts = WeakContextsWrapper::make_shared(); |
| 107 | + if (!weak_contexts) { |
| 108 | + throw std::runtime_error("weak contexts vector is not valid"); |
| 109 | + } |
| 110 | + return weak_contexts; |
| 111 | +} |
42 | 112 |
|
43 | 113 | /// Count of contexts that wanted to initialize the logging system. |
| 114 | +static |
44 | 115 | size_t & |
45 | 116 | get_logging_reference_count() |
46 | 117 | { |
47 | 118 | static size_t ref_count = 0; |
48 | 119 | return ref_count; |
49 | 120 | } |
50 | 121 |
|
51 | | -using rclcpp::Context; |
52 | | - |
53 | 122 | extern "C" |
54 | 123 | { |
55 | 124 | static |
@@ -168,8 +237,8 @@ Context::init( |
168 | 237 |
|
169 | 238 | init_options_ = init_options; |
170 | 239 |
|
171 | | - std::lock_guard<std::mutex> lock(g_contexts_mutex); |
172 | | - g_contexts.push_back(this->shared_from_this()); |
| 240 | + weak_contexts_ = get_weak_contexts(); |
| 241 | + weak_contexts_->add_context(this->shared_from_this()); |
173 | 242 | } catch (const std::exception & e) { |
174 | 243 | ret = rcl_shutdown(rcl_context_.get()); |
175 | 244 | rcl_context_.reset(); |
@@ -238,16 +307,7 @@ Context::shutdown(const std::string & reason) |
238 | 307 | this->interrupt_all_sleep_for(); |
239 | 308 | this->interrupt_all_wait_sets(); |
240 | 309 | // remove self from the global contexts |
241 | | - std::lock_guard<std::mutex> context_lock(g_contexts_mutex); |
242 | | - for (auto it = g_contexts.begin(); it != g_contexts.end(); ) { |
243 | | - auto shared_context = it->lock(); |
244 | | - if (shared_context.get() == this) { |
245 | | - it = g_contexts.erase(it); |
246 | | - break; |
247 | | - } else { |
248 | | - ++it; |
249 | | - } |
250 | | - } |
| 310 | + weak_contexts_->remove_context(this); |
251 | 311 | // shutdown logger |
252 | 312 | if (logging_mutex_) { |
253 | 313 | // logging was initialized by this context |
@@ -396,17 +456,6 @@ Context::clean_up() |
396 | 456 | std::vector<Context::SharedPtr> |
397 | 457 | rclcpp::get_contexts() |
398 | 458 | { |
399 | | - std::lock_guard<std::mutex> lock(g_contexts_mutex); |
400 | | - std::vector<Context::SharedPtr> shared_contexts; |
401 | | - for (auto it = g_contexts.begin(); it != g_contexts.end(); /* noop */) { |
402 | | - auto context_ptr = it->lock(); |
403 | | - if (!context_ptr) { |
404 | | - // remove invalid weak context pointers |
405 | | - it = g_contexts.erase(it); |
406 | | - } else { |
407 | | - ++it; |
408 | | - shared_contexts.push_back(context_ptr); |
409 | | - } |
410 | | - } |
411 | | - return shared_contexts; |
| 459 | + WeakContextsWrapper::SharedPtr weak_contexts = get_weak_contexts(); |
| 460 | + return weak_contexts->get_contexts(); |
412 | 461 | } |
0 commit comments