@@ -103,6 +103,9 @@ void Blackboard::addSubtreeRemapping(StringView internal, StringView external)
103103
104104void Blackboard::debugMessage () const
105105{
106+ // Lock storage_mutex_ to prevent iterator invalidation from
107+ // concurrent modifications (BUG-5 fix).
108+ const std::unique_lock<std::mutex> storage_lock (storage_mutex_);
106109 for (const auto & [key, entry] : storage_)
107110 {
108111 auto port_type = entry->info .type ();
@@ -136,6 +139,9 @@ void Blackboard::debugMessage() const
136139
137140std::vector<StringView> Blackboard::getKeys () const
138141{
142+ // Lock storage_mutex_ to prevent iterator invalidation and
143+ // dangling StringView from concurrent modifications (BUG-6 fix).
144+ const std::unique_lock<std::mutex> storage_lock (storage_mutex_);
139145 if (storage_.empty ())
140146 {
141147 return {};
@@ -178,49 +184,94 @@ void Blackboard::createEntry(const std::string& key, const TypeInfo& info)
178184
179185void Blackboard::cloneInto (Blackboard& dst) const
180186{
181- // Lock both mutexes without risking lock-order inversion.
182- std::unique_lock<std::mutex> lk1 (storage_mutex_, std::defer_lock);
183- std::unique_lock<std::mutex> lk2 (dst.storage_mutex_ , std::defer_lock);
184- std::lock (lk1, lk2);
185-
186- // keys that are not updated must be removed.
187- std::unordered_set<std::string> keys_to_remove;
188- auto & dst_storage = dst.storage_ ;
189- for (const auto & [key, entry] : dst_storage)
187+ // We must never hold storage_mutex_ while locking entry_mutex, because
188+ // the script evaluation path (ExprAssignment::evaluate) does the reverse:
189+ // entry_mutex → storage_mutex_ (via entryInfo → getEntry).
190+ //
191+ // Strategy: collect shared_ptrs under storage_mutex_, release it,
192+ // then copy entry data under entry_mutex only.
193+
194+ struct CopyTask
190195 {
191- std::ignore = entry; // unused in this loop
192- keys_to_remove.insert (key);
193- }
196+ std::string key;
197+ std::shared_ptr<Entry> src;
198+ std::shared_ptr<Entry> dst; // nullptr when a new entry is needed
199+ };
194200
195- // update or create entries in dst_storage
196- for (const auto & [src_key, src_entry] : storage_)
201+ std::vector<CopyTask> tasks;
202+ std::vector<std::string> keys_to_remove;
203+
204+ // Step 1: snapshot src/dst entries under both storage_mutex_ locks.
197205 {
198- keys_to_remove.erase (src_key);
206+ std::unique_lock<std::mutex> lk1 (storage_mutex_, std::defer_lock);
207+ std::unique_lock<std::mutex> lk2 (dst.storage_mutex_ , std::defer_lock);
208+ std::lock (lk1, lk2);
209+
210+ std::unordered_set<std::string> dst_keys;
211+ for (const auto & [key, entry] : dst.storage_ )
212+ {
213+ dst_keys.insert (key);
214+ }
215+
216+ for (const auto & [src_key, src_entry] : storage_)
217+ {
218+ dst_keys.erase (src_key);
219+ auto it = dst.storage_ .find (src_key);
220+ if (it != dst.storage_ .end ())
221+ {
222+ tasks.push_back ({ src_key, src_entry, it->second });
223+ }
224+ else
225+ {
226+ tasks.push_back ({ src_key, src_entry, nullptr });
227+ }
228+ }
229+
230+ for (const auto & key : dst_keys)
231+ {
232+ keys_to_remove.push_back (key);
233+ }
234+ }
235+ // storage_mutex_ locks released here
199236
200- auto it = dst_storage.find (src_key);
201- if (it != dst_storage.end ())
237+ // Step 2: copy entry data under entry_mutex only (BUG-3 fix).
238+ std::vector<std::pair<std::string, std::shared_ptr<Entry>>> new_entries;
239+
240+ for (auto & task : tasks)
241+ {
242+ if (task.dst )
202243 {
203- // overwrite
204- auto & dst_entry = it-> second ;
205- dst_entry ->string_converter = src_entry ->string_converter ;
206- dst_entry ->value = src_entry ->value ;
207- dst_entry ->info = src_entry ->info ;
208- dst_entry ->sequence_id ++;
209- dst_entry ->stamp = std::chrono::steady_clock::now ().time_since_epoch ();
244+ // overwrite existing entry
245+ std::scoped_lock entry_locks (task. src -> entry_mutex , task. dst -> entry_mutex ) ;
246+ task. dst ->string_converter = task. src ->string_converter ;
247+ task. dst ->value = task. src ->value ;
248+ task. dst ->info = task. src ->info ;
249+ task. dst ->sequence_id ++;
250+ task. dst ->stamp = std::chrono::steady_clock::now ().time_since_epoch ();
210251 }
211252 else
212253 {
213- // create new
214- auto new_entry = std::make_shared<Entry>(src_entry->info );
215- new_entry->value = src_entry->value ;
216- new_entry->string_converter = src_entry->string_converter ;
217- dst_storage.insert ({ src_key, new_entry });
254+ // create new entry from src
255+ std::scoped_lock src_lock (task.src ->entry_mutex );
256+ auto new_entry = std::make_shared<Entry>(task.src ->info );
257+ new_entry->value = task.src ->value ;
258+ new_entry->string_converter = task.src ->string_converter ;
259+ new_entries.emplace_back (task.key , std::move (new_entry));
218260 }
219261 }
220262
221- for (const auto & key : keys_to_remove)
263+ // Step 3: insert new entries and remove stale ones under dst.storage_mutex_.
264+ if (!new_entries.empty () || !keys_to_remove.empty ())
222265 {
223- dst_storage.erase (key);
266+ const std::unique_lock<std::mutex> dst_lock (dst.storage_mutex_ );
267+ for (auto & [key, entry] : new_entries)
268+ {
269+ dst.storage_ .insert ({ key, std::move (entry) });
270+ }
271+ for (const auto & key : keys_to_remove)
272+ {
273+ dst.storage_ .erase (key);
274+ }
224275 }
225276}
226277
@@ -317,6 +368,8 @@ void ImportBlackboardFromJSON(const nlohmann::json& json, Blackboard& blackboard
317368 blackboard.createEntry (it.key (), res->second );
318369 entry = blackboard.getEntry (it.key ());
319370 }
371+ // Lock entry_mutex before writing to prevent data races (BUG-4 fix).
372+ std::scoped_lock lk (entry->entry_mutex );
320373 entry->value = res->first ;
321374 }
322375 }
0 commit comments