@@ -2082,6 +2082,7 @@ TEST_P(EntityComponentManagerFixture, SetChanged)
2082
2082
auto c2 = manager.CreateComponent <IntComponent>(e2 , IntComponent (456 ));
2083
2083
2084
2084
EXPECT_TRUE (manager.HasOneTimeComponentChanges ());
2085
+ EXPECT_EQ (0u , manager.ComponentTypesWithPeriodicChanges ().size ());
2085
2086
EXPECT_EQ (ComponentState::OneTimeChange,
2086
2087
manager.ComponentState (e1 , c1.first ));
2087
2088
EXPECT_EQ (ComponentState::OneTimeChange,
@@ -2093,16 +2094,39 @@ TEST_P(EntityComponentManagerFixture, SetChanged)
2093
2094
// updated
2094
2095
manager.RunSetAllComponentsUnchanged ();
2095
2096
EXPECT_FALSE (manager.HasOneTimeComponentChanges ());
2097
+ EXPECT_EQ (0u , manager.ComponentTypesWithPeriodicChanges ().size ());
2096
2098
EXPECT_EQ (ComponentState::NoChange,
2097
2099
manager.ComponentState (e1 , c1.first ));
2098
2100
EXPECT_EQ (ComponentState::NoChange,
2099
2101
manager.ComponentState (e2 , c2.first ));
2100
2102
2101
2103
// Mark as changed
2102
2104
manager.SetChanged (e1 , c1.first , ComponentState::PeriodicChange);
2105
+
2106
+ // check that only e1 c1 is serialized into a message
2107
+ msgs::SerializedStateMap stateMsg;
2108
+ manager.State (stateMsg);
2109
+ {
2110
+ ASSERT_EQ (1 , stateMsg.entities_size ());
2111
+
2112
+ auto iter = stateMsg.entities ().find (e1 );
2113
+ const auto &e1Msg = iter->second ;
2114
+ EXPECT_EQ (e1 , e1Msg.id ());
2115
+ ASSERT_EQ (1 , e1Msg.components_size ());
2116
+
2117
+ auto compIter = e1Msg.components ().begin ();
2118
+ const auto &e1c1Msg = compIter->second ;
2119
+ EXPECT_EQ (IntComponent::typeId, e1c1Msg.type ());
2120
+ EXPECT_EQ (123 , std::stoi (e1c1Msg.component ()));
2121
+ }
2122
+
2103
2123
manager.SetChanged (e2 , c2.first , ComponentState::OneTimeChange);
2104
2124
2105
2125
EXPECT_TRUE (manager.HasOneTimeComponentChanges ());
2126
+ // Expect a single component type to be marked as PeriodicChange
2127
+ ASSERT_EQ (1u , manager.ComponentTypesWithPeriodicChanges ().size ());
2128
+ EXPECT_EQ (IntComponent ().TypeId (),
2129
+ *manager.ComponentTypesWithPeriodicChanges ().begin ());
2106
2130
EXPECT_EQ (ComponentState::PeriodicChange,
2107
2131
manager.ComponentState (e1 , c1.first ));
2108
2132
EXPECT_EQ (ComponentState::OneTimeChange,
@@ -2112,6 +2136,7 @@ TEST_P(EntityComponentManagerFixture, SetChanged)
2112
2136
EXPECT_TRUE (manager.RemoveComponent (e1 , c1.first ));
2113
2137
2114
2138
EXPECT_TRUE (manager.HasOneTimeComponentChanges ());
2139
+ EXPECT_EQ (0u , manager.ComponentTypesWithPeriodicChanges ().size ());
2115
2140
EXPECT_EQ (ComponentState::NoChange,
2116
2141
manager.ComponentState (e1 , c1.first ));
2117
2142
0 commit comments