From 28db59046928137c39accf0ee93485ef7b729b03 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 1 Dec 2022 15:45:38 +0100 Subject: [PATCH 1/2] Fixed Fortress tests related to lights MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- src/SdfEntityCreator_TEST.cc | 20 ++++++++-------- src/Server_TEST.cc | 4 ++-- src/SimulationRunner_TEST.cc | 8 +++---- test/integration/log_system.cc | 2 +- test/integration/recreate_entities.cc | 8 +++---- test/integration/scene_broadcaster_system.cc | 24 ++++++++++---------- test/integration/user_commands.cc | 24 ++++++++++---------- 7 files changed, 46 insertions(+), 44 deletions(-) diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 6c9c6247e7..9cb304b0f4 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -107,8 +107,9 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_TRUE(this->ecm.HasComponentType(components::LaserRetro::typeId)); // Check entities - // 1 x world + 5 x model + 5 x link + 5 x collision + 5 x visual + 1 x light - EXPECT_EQ(22u, this->ecm.EntityCount()); + // 1 x world + 5 x model + 5 x link + 5 x collision + 5 x visual + + // 1 x light (light + visual) + EXPECT_EQ(23u, this->ecm.EntityCount()); // Check worlds unsigned int worldCount{0}; @@ -684,8 +685,8 @@ TEST_F(SdfEntityCreatorTest, CreateLights) creator.CreateEntities(root.WorldByIndex(0)); // Check entities - // 1 x world + 1 x model + 1 x link + 1 x visual + 4 x light - EXPECT_EQ(8u, this->ecm.EntityCount()); + // 1 x world + 1 x model + 1 x link + 1 x visual + 4 x light (light + visual) + EXPECT_EQ(12u, this->ecm.EntityCount()); // Check worlds unsigned int worldCount{0}; @@ -1106,8 +1107,9 @@ TEST_F(SdfEntityCreatorTest, RemoveEntities) creator.CreateEntities(root.WorldByIndex(0)); // Check entities - // 1 x world + 4 x model + 4 x link + 4 x collision + 4 x visual + 1 x light - EXPECT_EQ(22u, this->ecm.EntityCount()); + // 1 x world + 4 x model + 4 x link + 4 x collision + 4 x visual + // + 1 x light (light + visual) + EXPECT_EQ(23u, this->ecm.EntityCount()); auto world = this->ecm.EntityByComponents(components::World()); EXPECT_NE(kNullEntity, world); @@ -1133,7 +1135,7 @@ TEST_F(SdfEntityCreatorTest, RemoveEntities) creator.RequestRemoveEntity(models.front()); this->ecm.ProcessEntityRemovals(); - EXPECT_EQ(18u, this->ecm.EntityCount()); + EXPECT_EQ(19u, this->ecm.EntityCount()); models = this->ecm.ChildrenByComponents(world, components::Model()); ASSERT_EQ(4u, models.size()); @@ -1156,7 +1158,7 @@ TEST_F(SdfEntityCreatorTest, RemoveEntities) creator.RequestRemoveEntity(models.front(), false); this->ecm.ProcessEntityRemovals(); - EXPECT_EQ(17u, this->ecm.EntityCount()); + EXPECT_EQ(18u, this->ecm.EntityCount()); // There's only 1 model left models = this->ecm.ChildrenByComponents(world, components::Model()); @@ -1210,7 +1212,7 @@ TEST_F(SdfEntityCreatorTest, RemoveEntities) visualCount++; return true; }); - EXPECT_EQ(4u, visualCount); + EXPECT_EQ(5u, visualCount); } template diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 6a95bf93b9..969c0259e1 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -348,7 +348,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig)) EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); EXPECT_EQ(0u, *server.IterationCount()); - EXPECT_EQ(24u, *server.EntityCount()); + EXPECT_EQ(25u, *server.EntityCount()); EXPECT_EQ(3u, *server.SystemCount()); EXPECT_TRUE(server.HasEntity("box")); @@ -391,7 +391,7 @@ TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfRootServerConfig)) EXPECT_FALSE(*server.Running(0)); EXPECT_TRUE(*server.Paused()); EXPECT_EQ(0u, *server.IterationCount()); - EXPECT_EQ(24u, *server.EntityCount()); + EXPECT_EQ(25u, *server.EntityCount()); EXPECT_EQ(3u, *server.SystemCount()); EXPECT_TRUE(server.HasEntity("box")); diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 4dbae0cd04..39901310a4 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -150,8 +150,8 @@ TEST_P(SimulationRunnerTest, CreateEntities) // Check entities // 1 x world + 1 x (default) level + 1 x wind + 5 x model + 5 x link + 5 x - // collision + 5 x visual + 1 x light - EXPECT_EQ(24u, runner.EntityCompMgr().EntityCount()); + // collision + 5 x visual + 1 x light (light + visual) + EXPECT_EQ(25u, runner.EntityCompMgr().EntityCount()); // Check worlds unsigned int worldCount{0}; @@ -656,8 +656,8 @@ TEST_P(SimulationRunnerTest, CreateLights) // Check entities // 1 x world + 1 x (default) level + 1 x wind + 1 x model + 1 x link + 1 x - // visual + 4 x light - EXPECT_EQ(10u, runner.EntityCompMgr().EntityCount()); + // visual + 4 x light (light + visual) + EXPECT_EQ(14u, runner.EntityCompMgr().EntityCount()); // Check worlds unsigned int worldCount{0}; diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 325b7c2988..3dedde8d77 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -759,7 +759,7 @@ TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RecordAndPlayback)) msgs::SerializedStateMap stateMsg; stateMsg.ParseFromString(recordedIter->Data()); // entity size = 28 in dbl pendulum + 4 in nested model - EXPECT_EQ(32, stateMsg.entities_size()); + EXPECT_EQ(33, stateMsg.entities_size()); EXPECT_NE(batch.end(), ++recordedIter); // Playback config diff --git a/test/integration/recreate_entities.cc b/test/integration/recreate_entities.cc index 14e8c4998c..97ab6eb9f2 100644 --- a/test/integration/recreate_entities.cc +++ b/test/integration/recreate_entities.cc @@ -135,8 +135,8 @@ TEST_F(RecreateEntitiesFixture, // Check entities // 1 x world + 1 x (default) level + 1 x wind + 5 x model + 5 x link + 5 x - // collision + 5 x visual + 1 x light - EXPECT_EQ(24u, ecm->EntityCount()); + // collision + 5 x visual + 1 x light (light + visual) + EXPECT_EQ(25u, ecm->EntityCount()); Entity worldEntity = ecm->EntityByComponents(components::World()); @@ -379,8 +379,8 @@ TEST_F(RecreateEntitiesFixture, { // Check entities // 1 x world + 1 x (default) level + 1 x wind + 5 x model + 5 x link + 5 x - // collision + 5 x visual + 1 x light - EXPECT_EQ(48u, ecm->EntityCount()); + // collision + 5 x visual + 1 x light (light + visual) + EXPECT_EQ(49u, ecm->EntityCount()); Entity worldEntity = ecm->EntityByComponents(components::World()); diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index ac452e6955..c1f9314bc0 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -64,7 +64,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseInfo)) gazebo::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - EXPECT_EQ(24u, *server.EntityCount()); + EXPECT_EQ(25u, *server.EntityCount()); // Create pose subscriber transport::Node node; @@ -76,7 +76,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseInfo)) ASSERT_TRUE(_msg.header().has_stamp()); EXPECT_LT(0, _msg.header().stamp().sec() + _msg.header().stamp().nsec()); - EXPECT_EQ(16, _msg.pose_size()); + EXPECT_EQ(17, _msg.pose_size()); std::map entityMap; for (auto p = 0; p < _msg.pose_size(); ++p) @@ -84,7 +84,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseInfo)) entityMap.insert(std::make_pair(_msg.pose(p).id(), _msg.pose(p).name())); } - EXPECT_EQ(16u, entityMap.size()); + EXPECT_EQ(17u, entityMap.size()); received = true; }; @@ -114,7 +114,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) gazebo::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - EXPECT_EQ(24u, *server.EntityCount()); + EXPECT_EQ(25u, *server.EntityCount()); // Run server server.Run(true, 1, false); @@ -160,7 +160,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneGraph)) gazebo::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - EXPECT_EQ(24u, *server.EntityCount()); + EXPECT_EQ(25u, *server.EntityCount()); // Run server server.Run(true, 1, false); @@ -200,7 +200,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopic)) gazebo::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - EXPECT_EQ(24u, *server.EntityCount()); + EXPECT_EQ(25u, *server.EntityCount()); // Create requester transport::Node node; @@ -297,7 +297,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeletedTopic)) EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - const std::size_t initEntityCount = 24; + const std::size_t initEntityCount = 25; EXPECT_EQ(initEntityCount, *server.EntityCount()); // Subscribe to deletions @@ -358,7 +358,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedModel)) EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - const std::size_t initEntityCount = 24; + const std::size_t initEntityCount = 25; EXPECT_EQ(initEntityCount, *server.EntityCount()); server.Run(true, 1, false); @@ -427,7 +427,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) gazebo::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - EXPECT_EQ(24u, *server.EntityCount()); + EXPECT_EQ(25u, *server.EntityCount()); transport::Node node; // Run server @@ -457,7 +457,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) [&](const msgs::SerializedStepMap &_res, const bool _success) { EXPECT_TRUE(_success); - checkMsg(_res, 24); + checkMsg(_res, 25); }; std::function cb2 = [&](const msgs::SerializedStepMap &_res) @@ -469,7 +469,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) std::function cbAsync = [&](const msgs::SerializedStepMap &_res) { - checkMsg(_res, 24); + checkMsg(_res, 25); }; // The request is blocking even though it's meant to be async, so we spin a @@ -538,7 +538,7 @@ TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StateStatic)) gazebo::Server server(serverConfig); EXPECT_FALSE(server.Running()); EXPECT_FALSE(*server.Running(0)); - EXPECT_EQ(8u, *server.EntityCount()); + EXPECT_EQ(9u, *server.EntityCount()); transport::Node node; // Run server diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 47b2f7f219..3052a6985a 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -219,7 +219,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Create)) // Run an iteration and check it was created server.Run(true, 1, false); - EXPECT_EQ(entityCount + 1, ecm->EntityCount()); + EXPECT_EQ(entityCount + 2, ecm->EntityCount()); entityCount = ecm->EntityCount(); auto light = ecm->EntityByComponents(components::Name("spawned_light")); @@ -238,7 +238,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Create)) // Run an iteration and check it was created server.Run(true, 1, false); - EXPECT_EQ(entityCount + 1, ecm->EntityCount()); + EXPECT_EQ(entityCount + 2, ecm->EntityCount()); entityCount = ecm->EntityCount(); light = ecm->EntityByComponents(components::Name("light_test")); @@ -292,7 +292,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Create)) // Run an iteration and check only the 1st was created server.Run(true, 1, false); - EXPECT_EQ(entityCount + 1, ecm->EntityCount()); + EXPECT_EQ(entityCount + 2, ecm->EntityCount()); entityCount = ecm->EntityCount(); EXPECT_EQ(kNullEntity, ecm->EntityByComponents( @@ -369,8 +369,8 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // Check entities // 1 x world + 1 x (default) level + 1 x wind + 5 x model + 5 x link + 5 x - // collision + 5 x visual + 1 x light - EXPECT_EQ(24u, ecm->EntityCount()); + // collision + 5 x visual + 1 x light (light + visual) + EXPECT_EQ(25u, ecm->EntityCount()); // Entity remove by name msgs::Entity req; @@ -393,7 +393,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // Run an iteration and check it was removed server.Run(true, 1, false); - EXPECT_EQ(20u, ecm->EntityCount()); + EXPECT_EQ(21u, ecm->EntityCount()); EXPECT_EQ(kNullEntity, ecm->EntityByComponents(components::Model(), components::Name("box"))); @@ -416,7 +416,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // Run an iteration and check it was removed server.Run(true, 1, false); - EXPECT_EQ(16u, ecm->EntityCount()); + EXPECT_EQ(17u, ecm->EntityCount()); EXPECT_EQ(kNullEntity, ecm->EntityByComponents(components::Model(), components::Name("sphere"))); @@ -435,7 +435,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // Run an iteration and check it was not removed server.Run(true, 1, false); - EXPECT_EQ(16u, ecm->EntityCount()); + EXPECT_EQ(17u, ecm->EntityCount()); EXPECT_NE(kNullEntity, ecm->EntityByComponents(components::Link(), components::Name("cylinder_link"))); @@ -456,7 +456,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // Run an iteration and check cylinder was removed and light wasn't server.Run(true, 1, false); - EXPECT_EQ(12u, ecm->EntityCount()); + EXPECT_EQ(13u, ecm->EntityCount()); EXPECT_EQ(kNullEntity, ecm->EntityByComponents(components::Model(), components::Name("cylinder"))); @@ -475,7 +475,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // Run an iteration and check nothing was removed server.Run(true, 1, false); - EXPECT_EQ(12u, ecm->EntityCount()); + EXPECT_EQ(13u, ecm->EntityCount()); EXPECT_NE(kNullEntity, ecm->EntityByComponents(components::Name("sun"))); @@ -489,7 +489,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // Run an iteration and check nothing was removed server.Run(true, 1, false); - EXPECT_EQ(12u, ecm->EntityCount()); + EXPECT_EQ(13u, ecm->EntityCount()); // Unsupported type - fails to remove req.Clear(); @@ -502,7 +502,7 @@ TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) // Run an iteration and check nothing was removed server.Run(true, 1, false); - EXPECT_EQ(12u, ecm->EntityCount()); + EXPECT_EQ(13u, ecm->EntityCount()); EXPECT_NE(kNullEntity, ecm->EntityByComponents(components::Name("sun"))); From ac9eaa2a8916231abfe27e187ef9222309d45ef5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 1 Dec 2022 16:24:27 +0100 Subject: [PATCH 2/2] Fix gui tests MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- src/gui/Gui_TEST.cc | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index 8f3d69e42d..16ebc6171d 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -34,7 +34,10 @@ #include "../../test/helpers/EnvTestFixture.hh" int gg_argc = 1; -char **gg_argv = new char *[gg_argc]; +char* gg_argv[] = +{ + reinterpret_cast(const_cast("./gui_test")), +}; using namespace ignition; using namespace ignition::gazebo::gui; @@ -269,4 +272,3 @@ TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(QuickStart)) app->exec(); checkingThread.join(); } -