diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index f3932a07b0..e4417014a6 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -2009,6 +2009,19 @@ TEST_P(EntityComponentManagerFixture, SetChanged) manager.ComponentState(e2, c2.first)); } +////////////////////////////////////////////////// +TEST_P(EntityComponentManagerFixture, SetEntityCreateOffset) +{ + // First entity should have a value of 1. + Entity entity = manager.CreateEntity(); + EXPECT_EQ(1u, entity); + + // Apply an offset. + manager.SetEntityCreateOffset(1000); + Entity entity2 = manager.CreateEntity(); + EXPECT_EQ(1001u, entity2); +} + // Run multiple times. We want to make sure that static globals don't cause // problems. INSTANTIATE_TEST_CASE_P(EntityComponentManagerRepeat, diff --git a/src/systems/log/LogPlayback.cc b/src/systems/log/LogPlayback.cc index 32ab860c72..f9d62da1f4 100644 --- a/src/systems/log/LogPlayback.cc +++ b/src/systems/log/LogPlayback.cc @@ -211,7 +211,7 @@ void LogPlayback::Configure(const Entity &, // Set the entity offset. // \todo This number should be included in the log file. - _ecm.SetEntityOffset(90000); + _ecm.SetEntityCreateOffset(math::MAX_I64 / 2); // If path is a file, assume it is a compressed file // (Otherwise assume it is a directory containing recorded files.)