@@ -385,7 +385,8 @@ void EntityComponentManager::Each(typename identity<std::function<
385
385
// function.
386
386
for (const Entity entity : view->Entities ())
387
387
{
388
- if (!std::apply (_f, view->EntityComponentConstData (entity)))
388
+ if (!std::apply (_f,
389
+ view->template EntityComponentConstData <ComponentTypeTs...>(entity)))
389
390
{
390
391
break ;
391
392
}
@@ -405,7 +406,8 @@ void EntityComponentManager::Each(typename identity<std::function<
405
406
// function.
406
407
for (const Entity entity : view->Entities ())
407
408
{
408
- if (!std::apply (_f, view->EntityComponentData (entity)))
409
+ if (!std::apply (_f,
410
+ view->template EntityComponentData <ComponentTypeTs...>(entity)))
409
411
{
410
412
break ;
411
413
}
@@ -434,7 +436,8 @@ void EntityComponentManager::EachNew(typename identity<std::function<
434
436
// function.
435
437
for (const Entity entity : view->NewEntities ())
436
438
{
437
- if (!std::apply (_f, view->EntityComponentData (entity)))
439
+ if (!std::apply (_f,
440
+ view->template EntityComponentData <ComponentTypeTs...>(entity)))
438
441
{
439
442
break ;
440
443
}
@@ -455,7 +458,7 @@ void EntityComponentManager::EachNew(typename identity<std::function<
455
458
// function.
456
459
for (const Entity entity : view->NewEntities ())
457
460
{
458
- if (!std::apply (_f, view->EntityComponentConstData (entity)))
461
+ if (!std::apply (_f, view->template EntityComponentConstData <ComponentTypeTs...> (entity)))
459
462
{
460
463
break ;
461
464
}
@@ -476,7 +479,8 @@ void EntityComponentManager::EachRemoved(typename identity<std::function<
476
479
// function.
477
480
for (const Entity entity : view->ToRemoveEntities ())
478
481
{
479
- if (!std::apply (_f, view->EntityComponentConstData (entity)))
482
+ if (!std::apply (_f,
483
+ view->template EntityComponentConstData <ComponentTypeTs...>(entity)))
480
484
{
481
485
break ;
482
486
}
@@ -485,15 +489,15 @@ void EntityComponentManager::EachRemoved(typename identity<std::function<
485
489
486
490
// ////////////////////////////////////////////////
487
491
template <typename ...ComponentTypeTs>
488
- detail::View<ComponentTypeTs...> *EntityComponentManager::FindView () const
492
+ detail::View *EntityComponentManager::FindView () const
489
493
{
490
494
auto viewKey = std::vector<ComponentTypeId>{ComponentTypeTs::typeId...};
491
495
492
496
auto baseViewMutexPair = this ->FindView (viewKey);
493
497
auto baseViewPtr = baseViewMutexPair.first ;
494
498
if (nullptr != baseViewPtr)
495
499
{
496
- auto view = static_cast <detail::View<ComponentTypeTs...> *>(baseViewPtr);
500
+ auto view = static_cast <detail::View*>(baseViewPtr);
497
501
498
502
std::unique_ptr<std::lock_guard<std::mutex>> viewLock;
499
503
if (this ->LockAddingEntitiesToViews ())
@@ -527,28 +531,29 @@ detail::View<ComponentTypeTs...> *EntityComponentManager::FindView() const
527
531
}
528
532
529
533
// 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...});
531
536
532
537
for (const auto &vertex : this ->Entities ().Vertices ())
533
538
{
534
539
Entity entity = vertex.first ;
535
540
536
541
// 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 ()))
538
543
continue ;
539
544
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>(
544
550
entity)...);
545
551
if (this ->IsMarkedForRemoval (entity))
546
- view. MarkEntityToRemove (entity);
552
+ view-> MarkEntityToRemove (entity);
547
553
}
548
554
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);
552
557
}
553
558
554
559
// ////////////////////////////////////////////////
0 commit comments