Skip to content

Commit b4274db

Browse files
committed
Potential fix for ECM segfault at exit
Signed-off-by: Addisu Z. Taddese <[email protected]>
1 parent 912e2ce commit b4274db

File tree

5 files changed

+239
-185
lines changed

5 files changed

+239
-185
lines changed

include/ignition/gazebo/EntityComponentManager.hh

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -738,7 +738,7 @@ namespace ignition
738738
/// \tparam ComponentTypeTs All the component types that define a view.
739739
/// \return A pointer to the view.
740740
private: template<typename ...ComponentTypeTs>
741-
detail::View<ComponentTypeTs...> *FindView() const;
741+
detail::View *FindView() const;
742742

743743
/// \brief Find a view based on the provided component type ids.
744744
/// \param[in] _types The component type ids that serve as a key into

include/ignition/gazebo/detail/EntityComponentManager.hh

Lines changed: 22 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -385,7 +385,8 @@ void EntityComponentManager::Each(typename identity<std::function<
385385
// function.
386386
for (const Entity entity : view->Entities())
387387
{
388-
if (!std::apply(_f, view->EntityComponentConstData(entity)))
388+
if (!std::apply(_f,
389+
view->template EntityComponentConstData<ComponentTypeTs...>(entity)))
389390
{
390391
break;
391392
}
@@ -405,7 +406,8 @@ void EntityComponentManager::Each(typename identity<std::function<
405406
// function.
406407
for (const Entity entity : view->Entities())
407408
{
408-
if (!std::apply(_f, view->EntityComponentData(entity)))
409+
if (!std::apply(_f,
410+
view->template EntityComponentData<ComponentTypeTs...>(entity)))
409411
{
410412
break;
411413
}
@@ -434,7 +436,8 @@ void EntityComponentManager::EachNew(typename identity<std::function<
434436
// function.
435437
for (const Entity entity : view->NewEntities())
436438
{
437-
if (!std::apply(_f, view->EntityComponentData(entity)))
439+
if (!std::apply(_f,
440+
view->template EntityComponentData<ComponentTypeTs...>(entity)))
438441
{
439442
break;
440443
}
@@ -455,7 +458,7 @@ void EntityComponentManager::EachNew(typename identity<std::function<
455458
// function.
456459
for (const Entity entity : view->NewEntities())
457460
{
458-
if (!std::apply(_f, view->EntityComponentConstData(entity)))
461+
if (!std::apply(_f, view->template EntityComponentConstData<ComponentTypeTs...>(entity)))
459462
{
460463
break;
461464
}
@@ -476,7 +479,8 @@ void EntityComponentManager::EachRemoved(typename identity<std::function<
476479
// function.
477480
for (const Entity entity : view->ToRemoveEntities())
478481
{
479-
if (!std::apply(_f, view->EntityComponentConstData(entity)))
482+
if (!std::apply(_f,
483+
view->template EntityComponentConstData<ComponentTypeTs...>(entity)))
480484
{
481485
break;
482486
}
@@ -485,15 +489,15 @@ void EntityComponentManager::EachRemoved(typename identity<std::function<
485489

486490
//////////////////////////////////////////////////
487491
template<typename ...ComponentTypeTs>
488-
detail::View<ComponentTypeTs...> *EntityComponentManager::FindView() const
492+
detail::View *EntityComponentManager::FindView() const
489493
{
490494
auto viewKey = std::vector<ComponentTypeId>{ComponentTypeTs::typeId...};
491495

492496
auto baseViewMutexPair = this->FindView(viewKey);
493497
auto baseViewPtr = baseViewMutexPair.first;
494498
if (nullptr != baseViewPtr)
495499
{
496-
auto view = static_cast<detail::View<ComponentTypeTs...>*>(baseViewPtr);
500+
auto view = static_cast<detail::View*>(baseViewPtr);
497501

498502
std::unique_ptr<std::lock_guard<std::mutex>> viewLock;
499503
if (this->LockAddingEntitiesToViews())
@@ -527,28 +531,29 @@ detail::View<ComponentTypeTs...> *EntityComponentManager::FindView() const
527531
}
528532

529533
// create a new view if one wasn't found
530-
detail::View<ComponentTypeTs...> view;
534+
auto view = std::make_unique<detail::View>(
535+
std::set<ComponentTypeId>{ComponentTypeTs::typeId...});
531536

532537
for (const auto &vertex : this->Entities().Vertices())
533538
{
534539
Entity entity = vertex.first;
535540

536541
// only add entities to the view that have all of the components in viewKey
537-
if (!this->EntityMatches(entity, view.ComponentTypes()))
542+
if (!this->EntityMatches(entity, view->ComponentTypes()))
538543
continue;
539544

540-
view.AddEntityWithConstComps(entity, this->IsNewEntity(entity),
541-
this->Component<ComponentTypeTs>(entity)...);
542-
view.AddEntityWithComps(entity, this->IsNewEntity(entity),
543-
const_cast<EntityComponentManager*>(this)->Component<ComponentTypeTs>(
545+
view->AddEntityWithConstComps(entity, this->IsNewEntity(entity),
546+
this->Component<ComponentTypeTs>(entity)...);
547+
view->AddEntityWithComps(
548+
entity, this->IsNewEntity(entity),
549+
const_cast<EntityComponentManager *>(this)->Component<ComponentTypeTs>(
544550
entity)...);
545551
if (this->IsMarkedForRemoval(entity))
546-
view.MarkEntityToRemove(entity);
552+
view->MarkEntityToRemove(entity);
547553
}
548554

549-
baseViewPtr = this->AddView(viewKey,
550-
std::make_unique<detail::View<ComponentTypeTs...>>(view));
551-
return static_cast<detail::View<ComponentTypeTs...>*>(baseViewPtr);
555+
baseViewPtr = this->AddView(viewKey, std::move(view));
556+
return static_cast<detail::View *>(baseViewPtr);
552557
}
553558

554559
//////////////////////////////////////////////////

0 commit comments

Comments
 (0)