diff --git a/Changelog.md b/Changelog.md index 8f117d5b8d..69d421695a 100644 --- a/Changelog.md +++ b/Changelog.md @@ -969,6 +969,41 @@ ## Ignition Gazebo 4.x +### Ignition Gazebo 4.13.0 (2021-11-15) + +1. Prevent creation of spurious `` elements when saving worlds + * [Pull request #1192](https://github.com/ignitionrobotics/ign-gazebo/pull/1192) + +1. Add support for tracked vehicles + * [Pull request #869](https://github.com/ignitionrobotics/ign-gazebo/pull/869) + +1. Add components to dynamically set joint limits + * [Pull request #847](https://github.com/ignitionrobotics/ign-gazebo/pull/847) + +1. Fix updating component from state + * [Pull request #1181](https://github.com/ignitionrobotics/ign-gazebo/pull/1181) + +1. Fix updating a component's data via SerializedState msg + * [Pull request #1149](https://github.com/ignitionrobotics/ign-gazebo/pull/1149) + +1. Sensor systems work if loaded after sensors + * [Pull request #1104](https://github.com/ignitionrobotics/ign-gazebo/pull/1104) + +1. Fix generation of systems library symlinks in build directory + * [Pull request #1160](https://github.com/ignitionrobotics/ign-gazebo/pull/1160) + +1. Edit material colors in component inspector + * [Pull request #1123](https://github.com/ignitionrobotics/ign-gazebo/pull/1123) + +1. Support setting the background color for sensors + * [Pull request #1147](https://github.com/ignitionrobotics/ign-gazebo/pull/1147) + +1. Use uint64_t for ComponentInspector Entity IDs + * [Pull request #1144](https://github.com/ignitionrobotics/ign-gazebo/pull/1144) + +1. Fix integers and floats on component inspector + * [Pull request #1143](https://github.com/ignitionrobotics/ign-gazebo/pull/1143) + ### Ignition Gazebo 4.12.0 (2021-10-22) 1. Fix performance issue with contact data and AABB updates. diff --git a/src/Component_TEST.cc b/src/Component_TEST.cc index 2202b05753..7e6864710d 100644 --- a/src/Component_TEST.cc +++ b/src/Component_TEST.cc @@ -17,6 +17,7 @@ #include #include +#include #include @@ -61,7 +62,8 @@ TEST_F(ComponentTest, ComponentCanBeCopiedAfterDefaultCtor) } ////////////////////////////////////////////////// -TEST_F(ComponentTest, DataByMove) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ComponentTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DataByMove)) { auto factory = components::Factory::Instance(); diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index 93463f6502..c2b14062c8 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -21,6 +21,7 @@ #include #include #include +#include #include #include "ignition/gazebo/components/CanonicalLink.hh" @@ -135,7 +136,8 @@ TEST_P(EntityComponentManagerFixture, InvalidComponentType) } ///////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, RemoveComponent) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(RemoveComponent)) { // Create some entities auto eInt = manager.CreateEntity(); @@ -212,7 +214,8 @@ TEST_P(EntityComponentManagerFixture, RemoveComponent) } ///////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EntitiesAndComponents) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EntitiesAndComponents)) { EXPECT_EQ(0u, manager.EntityCount()); @@ -299,7 +302,8 @@ TEST_P(EntityComponentManagerFixture, EntitiesAndComponents) } ///////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, ComponentValues) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ComponentValues)) { // Create some entities Entity eInt = manager.CreateEntity(); @@ -474,7 +478,8 @@ TEST_P(EntityComponentManagerFixture, ComponentValues) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, RebuildViews) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(RebuildViews)) { // Create some entities Entity eInt = manager.CreateEntity(); @@ -543,7 +548,8 @@ TEST_P(EntityComponentManagerFixture, RebuildViews) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, ViewsAddComponents) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ViewsAddComponents)) { // Create some entities Entity eInt = manager.CreateEntity(); @@ -616,7 +622,8 @@ TEST_P(EntityComponentManagerFixture, ViewsAddComponents) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, ViewsRemoveComponents) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ViewsRemoveComponents)) { // Create some entities Entity eInt = manager.CreateEntity(); @@ -690,7 +697,8 @@ TEST_P(EntityComponentManagerFixture, ViewsRemoveComponents) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, ViewsAddEntity) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ViewsAddEntity)) { // Create some entities Entity eInt = manager.CreateEntity(); @@ -779,7 +787,8 @@ TEST_P(EntityComponentManagerFixture, ViewsAddEntity) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, ViewsRemoveEntities) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ViewsRemoveEntities)) { // Create some entities Entity eInt = manager.CreateEntity(); @@ -915,7 +924,8 @@ TEST_P(EntityComponentManagerFixture, RemoveEntity) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, ViewsRemoveEntity) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ViewsRemoveEntity)) { // Create some entities Entity eInt = manager.CreateEntity(); @@ -1047,7 +1057,8 @@ int eachCount(EntityCompMgrTest &_manager) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachNewBasic) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachNewBasic)) { // Create entities Entity e1 = manager.CreateEntity(); @@ -1091,7 +1102,8 @@ TEST_P(EntityComponentManagerFixture, EachNewBasic) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachNewAfterRemoveComponent) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachNewAfterRemoveComponent)) { // Create entities Entity e1 = manager.CreateEntity(); @@ -1111,7 +1123,8 @@ TEST_P(EntityComponentManagerFixture, EachNewAfterRemoveComponent) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachNewRemoveComponentFromRemoveEntity) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachNewRemoveComponentFromRemoveEntity)) { // Create entities Entity e1 = manager.CreateEntity(); @@ -1131,7 +1144,8 @@ TEST_P(EntityComponentManagerFixture, EachNewRemoveComponentFromRemoveEntity) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachNewAddComponentToExistingEntity) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachNewAddComponentToExistingEntity)) { // Create entities Entity e1 = manager.CreateEntity(); @@ -1164,7 +1178,8 @@ TEST_P(EntityComponentManagerFixture, EachNewAddComponentToExistingEntity) } //////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachRemoveBasic) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachRemoveBasic)) { // Create an entities Entity e1 = manager.CreateEntity(); @@ -1218,7 +1233,8 @@ TEST_P(EntityComponentManagerFixture, EachRemoveAlreadyRemove) } //////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachRemoveAfterRebuild) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachRemoveAfterRebuild)) { // Test after rebuild Entity e1 = manager.CreateEntity(); @@ -1237,7 +1253,8 @@ TEST_P(EntityComponentManagerFixture, EachRemoveAfterRebuild) } //////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachRemoveAddComponentToRemoveEntity) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachRemoveAddComponentToRemoveEntity)) { Entity e1 = manager.CreateEntity(); auto comp1 = manager.CreateComponent(e1, IntComponent(123)); @@ -1255,7 +1272,8 @@ TEST_P(EntityComponentManagerFixture, EachRemoveAddComponentToRemoveEntity) } //////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachRemoveAllRemove) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachRemoveAllRemove)) { // Test when all entities are removed Entity e1 = manager.CreateEntity(); @@ -1274,7 +1292,8 @@ TEST_P(EntityComponentManagerFixture, EachRemoveAllRemove) } //////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachNewEachRemove) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachNewEachRemove)) { // Test EachNew and EachRemove together Entity e1 = manager.CreateEntity(); @@ -1304,7 +1323,8 @@ TEST_P(EntityComponentManagerFixture, EachNewEachRemove) } //////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EachGetsNewOldRemove) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachGetsNewOldRemove)) { // Test that an Each call gets new, old, and removed entities Entity e1 = manager.CreateEntity(); @@ -1399,7 +1419,8 @@ TEST_P(EntityComponentManagerFixture, EachAddRemoveComponent) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EntityByComponents) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EntityByComponents)) { // Create some entities Entity eInt = manager.CreateEntity(); @@ -1479,7 +1500,8 @@ TEST_P(EntityComponentManagerFixture, EntityByComponents) } ///////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, EntityGraph) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EntityGraph)) { EXPECT_EQ(0u, manager.EntityCount()); @@ -1618,7 +1640,7 @@ TEST_P(EntityComponentManagerFixture, EntityGraph) } ///////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, State) +TEST_P(EntityComponentManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) { // Entities and components Entity e1{1}; @@ -1899,7 +1921,8 @@ TEST_P(EntityComponentManagerFixture, State) } ///////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, ChangedStateComponents) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ChangedStateComponents)) { // Entity and component Entity e1{1}; @@ -2180,7 +2203,8 @@ TEST_P(EntityComponentManagerFixture, Descendants) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, SetChanged) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SetChanged)) { // Create entities Entity e1 = manager.CreateEntity(); @@ -2278,7 +2302,9 @@ TEST_P(EntityComponentManagerFixture, SetEntityCreateOffset) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, SerializedStateMapMsgAfterRemoveComponent) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32( + SerializedStateMapMsgAfterRemoveComponent)) { // Create entity Entity e1 = manager.CreateEntity(); @@ -2346,7 +2372,8 @@ TEST_P(EntityComponentManagerFixture, SerializedStateMapMsgAfterRemoveComponent) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, SerializedStateMsgAfterRemoveComponent) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SerializedStateMsgAfterRemoveComponent)) { // Create entity Entity e1 = manager.CreateEntity(); @@ -2410,7 +2437,8 @@ TEST_P(EntityComponentManagerFixture, SerializedStateMsgAfterRemoveComponent) ////////////////////////////////////////////////// // Verify SerializedStateMap message with no changed components, // but some removed components -TEST_P(EntityComponentManagerFixture, SerializedStateMapMsgCompsRemovedOnly) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SerializedStateMapMsgCompsRemovedOnly)) { // Create entity Entity e1 = manager.CreateEntity(); @@ -2454,7 +2482,8 @@ TEST_P(EntityComponentManagerFixture, SerializedStateMapMsgCompsRemovedOnly) ////////////////////////////////////////////////// // Verify that removed components are correctly filtered when creating a // SerializedStateMap message -TEST_P(EntityComponentManagerFixture, SetRemovedComponentsMsgTypesFilter) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SetRemovedComponentsMsgTypesFilter)) { // Create entity Entity e1 = manager.CreateEntity(); @@ -2495,7 +2524,9 @@ TEST_P(EntityComponentManagerFixture, SetRemovedComponentsMsgTypesFilter) } ////////////////////////////////////////////////// -TEST_P(EntityComponentManagerFixture, RemovedComponentsSyncBetweenServerAndGUI) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32( + RemovedComponentsSyncBetweenServerAndGUI)) { // Simulate the GUI's ECM EntityCompMgrTest guiManager; @@ -3020,7 +3051,8 @@ TEST_P(EntityComponentManagerFixture, PinnedEntity) ////////////////////////////////////////////////// /// \brief Test using msgs::SerializedStateMap and msgs::SerializedState /// to update existing component data between multiple ECMs -TEST_P(EntityComponentManagerFixture, StateMsgUpdateComponent) +TEST_P(EntityComponentManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(StateMsgUpdateComponent)) { // create 2 ECMs: one will be modified directly, and the other should be // updated to match the first via msgs::SerializedStateMap diff --git a/src/ModelCommandAPI_TEST.cc b/src/ModelCommandAPI_TEST.cc index 35a0463dbf..36eafc23f4 100644 --- a/src/ModelCommandAPI_TEST.cc +++ b/src/ModelCommandAPI_TEST.cc @@ -20,6 +20,7 @@ #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) @@ -72,7 +73,8 @@ std::string customExecStr(std::string _cmd) ///////////////////////////////////////////////// // Test `ign model` command when no Gazebo server is running. -TEST(ModelCommandAPI, NoServerRunning) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST(ModelCommandAPI, IGN_UTILS_TEST_DISABLED_ON_WIN32(NoServerRunning)) { const std::string cmd = kIgnModelCommand + "--list "; const std::string output = customExecStr(cmd); @@ -85,7 +87,7 @@ TEST(ModelCommandAPI, NoServerRunning) ///////////////////////////////////////////////// // Tests `ign model` command. -TEST(ModelCommandAPI, Commands) +TEST(ModelCommandAPI, IGN_UTILS_TEST_DISABLED_ON_WIN32(Commands)) { ignition::gazebo::ServerConfig serverConfig; // Using an static model to avoid any movements in the simulation. diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index eac28eef0c..12554dbf7e 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -127,7 +127,7 @@ TEST_F(SdfEntityCreatorTest, CreateEntities) EXPECT_EQ("default", _name->Data()); EXPECT_DOUBLE_EQ(0.001, _physics->Data().MaxStepSize()); - EXPECT_DOUBLE_EQ(1.0, _physics->Data().RealTimeFactor()); + EXPECT_DOUBLE_EQ(0.0, _physics->Data().RealTimeFactor()); worldCount++; diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 3599fda3ef..5c0cbe7058 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -21,6 +21,7 @@ #include #include #include +#include #include #include #include @@ -892,7 +893,9 @@ TEST_F(ElementUpdateFixture, WorldWithModelsExpandedWithOneIncluded) } ///////////////////////////////////////////////// -TEST_F(ElementUpdateFixture, WorldWithModelsUsingRelativeResourceURIs) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ElementUpdateFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(WorldWithModelsUsingRelativeResourceURIs)) { const auto includeUri = std::string("file://") + PROJECT_SOURCE_PATH + "/test/worlds/models/relative_resource_uri"; diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 2c11a7697e..e95e9bb8e8 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include #include "ignition/gazebo/components/AxisAlignedBox.hh" @@ -50,7 +51,8 @@ class ServerFixture : public InternalFixture<::testing::TestWithParam> }; ///////////////////////////////////////////////// -TEST_P(ServerFixture, DefaultServerConfig) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultServerConfig)) { ignition::gazebo::ServerConfig serverConfig; EXPECT_TRUE(serverConfig.SdfFile().empty()); @@ -158,7 +160,7 @@ TEST_P(ServerFixture, ServerConfigPluginInfo) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, ServerConfigRealPlugin) +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigRealPlugin)) { // Start server ServerConfig serverConfig; @@ -209,7 +211,8 @@ TEST_P(ServerFixture, ServerConfigRealPlugin) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, ServerConfigSensorPlugin) +TEST_P(ServerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigSensorPlugin)) { // Start server ServerConfig serverConfig; @@ -260,7 +263,7 @@ TEST_P(ServerFixture, ServerConfigSensorPlugin) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, SdfServerConfig) +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(SdfServerConfig)) { ignition::gazebo::ServerConfig serverConfig; @@ -293,7 +296,7 @@ TEST_P(ServerFixture, SdfServerConfig) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, ServerConfigLogRecord) +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigLogRecord)) { auto logPath = common::joinPaths( std::string(PROJECT_BINARY_PATH), "test_log_path"); @@ -332,7 +335,8 @@ TEST_P(ServerFixture, ServerConfigLogRecord) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, ServerConfigLogRecordCompress) +TEST_P(ServerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ServerConfigLogRecordCompress)) { auto logPath = common::joinPaths( std::string(PROJECT_BINARY_PATH), "test_log_path"); @@ -483,7 +487,7 @@ TEST_P(ServerFixture, RunNonBlocking) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, RunOnceUnpaused) +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunOnceUnpaused)) { gazebo::Server server; EXPECT_FALSE(server.Running()); @@ -530,7 +534,7 @@ TEST_P(ServerFixture, RunOnceUnpaused) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, RunOncePaused) +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RunOncePaused)) { gazebo::Server server; EXPECT_FALSE(server.Running()); @@ -620,7 +624,7 @@ TEST_P(ServerFixture, SigInt) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, AddSystemWhileRunning) +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemWhileRunning)) { ignition::gazebo::ServerConfig serverConfig; @@ -668,7 +672,7 @@ TEST_P(ServerFixture, AddSystemWhileRunning) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, AddSystemAfterLoad) +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(AddSystemAfterLoad)) { ignition::gazebo::ServerConfig serverConfig; @@ -742,7 +746,7 @@ TEST_P(ServerFixture, Seed) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, ResourcePath) +TEST_P(ServerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) { ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", (std::string(PROJECT_SOURCE_PATH) + "/test/worlds:" + diff --git a/src/SimulationRunner.cc b/src/SimulationRunner.cc index ae3b5af708..9264a41713 100644 --- a/src/SimulationRunner.cc +++ b/src/SimulationRunner.cc @@ -105,8 +105,15 @@ SimulationRunner::SimulationRunner(const sdf::World *_world, // So to get a given RTF, our desired period is: // // period = step_size / RTF - this->updatePeriod = std::chrono::nanoseconds( - static_cast(this->stepSize.count() / this->desiredRtf)); + if (this->desiredRtf < 1e-9) + { + this->updatePeriod = 0ms; + } + else + { + this->updatePeriod = std::chrono::nanoseconds( + static_cast(this->stepSize.count() / this->desiredRtf)); + } this->pauseConn = this->eventMgr.Connect( std::bind(&SimulationRunner::SetPaused, this, std::placeholders::_1)); diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index fbcb8d19af..cc9b33161a 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -21,6 +21,7 @@ #include #include #include +#include #include #include #include @@ -1073,7 +1074,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(0u, runner.CurrentInfo().iterations); EXPECT_EQ(0ms, runner.CurrentInfo().simTime); EXPECT_EQ(0ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(1ms, runner.StepSize()); runner.SetPaused(false); @@ -1086,7 +1087,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(100u, runner.CurrentInfo().iterations); EXPECT_EQ(100ms, runner.CurrentInfo().simTime); EXPECT_EQ(1ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(1ms, runner.StepSize()); int sleep = 0; @@ -1107,7 +1108,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(200u, runner.CurrentInfo().iterations); EXPECT_EQ(300ms, runner.CurrentInfo().simTime); EXPECT_EQ(2ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(2ms, runner.StepSize()); sleep = 0; @@ -1127,7 +1128,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(200u, runner.CurrentInfo().iterations); EXPECT_EQ(300ms, runner.CurrentInfo().simTime); EXPECT_EQ(2ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(2ms, runner.StepSize()); // Verify info published to /clock topic @@ -1145,7 +1146,7 @@ TEST_P(SimulationRunnerTest, Time) EXPECT_EQ(500ms, runner.CurrentInfo().simTime) << runner.CurrentInfo().simTime.count(); EXPECT_EQ(2ms, runner.CurrentInfo().dt); - EXPECT_EQ(1ms, runner.UpdatePeriod()); + EXPECT_EQ(0ms, runner.UpdatePeriod()); EXPECT_EQ(2ms, runner.StepSize()); sleep = 0; @@ -1183,7 +1184,8 @@ TEST_P(SimulationRunnerTest, Time) } ///////////////////////////////////////////////// -TEST_P(SimulationRunnerTest, LoadPlugins) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(SimulationRunnerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPlugins) ) { // Load SDF file sdf::Root root; @@ -1270,7 +1272,8 @@ TEST_P(SimulationRunnerTest, LoadPlugins) } ///////////////////////////////////////////////// -TEST_P(SimulationRunnerTest, LoadServerNoPlugins) +TEST_P(SimulationRunnerTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadServerNoPlugins) ) { sdf::Root rootWithout; rootWithout.Load(common::joinPaths(PROJECT_SOURCE_PATH, @@ -1292,7 +1295,8 @@ TEST_P(SimulationRunnerTest, LoadServerNoPlugins) } ///////////////////////////////////////////////// -TEST_P(SimulationRunnerTest, LoadServerConfigPlugins) +TEST_P(SimulationRunnerTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadServerConfigPlugins) ) { sdf::Root rootWithout; rootWithout.Load(common::joinPaths(PROJECT_SOURCE_PATH, @@ -1392,7 +1396,8 @@ TEST_P(SimulationRunnerTest, LoadServerConfigPlugins) } ///////////////////////////////////////////////// -TEST_P(SimulationRunnerTest, LoadPluginsDefault) +TEST_P(SimulationRunnerTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPluginsDefault) ) { sdf::Root rootWithout; rootWithout.Load(common::joinPaths(PROJECT_SOURCE_PATH, @@ -1413,7 +1418,8 @@ TEST_P(SimulationRunnerTest, LoadPluginsDefault) } ///////////////////////////////////////////////// -TEST_P(SimulationRunnerTest, LoadPluginsEvent) +TEST_P(SimulationRunnerTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LoadPluginsEvent) ) { // Load SDF file without plugins sdf::Root rootWithout; diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index 881bfb931b..c4fd4cda6d 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -42,7 +42,8 @@ class GuiTest : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // https://github.com/ignitionrobotics/ign-gazebo/issues/8 -TEST_F(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager)) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(GuiTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PathManager)) { common::Console::SetVerbosity(4); igndbg << "Start test" << std::endl; diff --git a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc index 7211d9e8ef..ab306bdd8b 100644 --- a/src/gui/plugins/visualize_lidar/VisualizeLidar.cc +++ b/src/gui/plugins/visualize_lidar/VisualizeLidar.cc @@ -291,8 +291,13 @@ void VisualizeLidar::Update(const UpdateInfo &, for (auto child : children) { std::string nextstring = lidarURIVec[i+1]; + auto comp = _ecm.Component(child); + if (!comp) + { + continue; + } std::string childname = std::string( - _ecm.Component(child)->Data()); + comp->Data()); if (nextstring.compare(childname) == 0) { parent = child; diff --git a/src/ign_TEST.cc b/src/ign_TEST.cc index a1d7e71871..5c3bcf6f7c 100644 --- a/src/ign_TEST.cc +++ b/src/ign_TEST.cc @@ -55,7 +55,8 @@ std::string customExecStr(std::string _cmd) } ///////////////////////////////////////////////// -TEST(CmdLine, Server) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(Server)) { std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + std::string(PROJECT_SOURCE_PATH) + "/test/worlds/plugins.sdf"; @@ -87,7 +88,7 @@ TEST(CmdLine, Server) } ///////////////////////////////////////////////// -TEST(CmdLine, CachedFuelWorld) +TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(CachedFuelWorld)) { std::string projectPath = std::string(PROJECT_SOURCE_PATH) + "/test/worlds"; ignition::common::setenv("IGN_FUEL_CACHE_PATH", projectPath.c_str()); @@ -101,7 +102,7 @@ TEST(CmdLine, CachedFuelWorld) } ///////////////////////////////////////////////// -TEST(CmdLine, GazeboServer) +TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(GazeboServer)) { std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + std::string(PROJECT_SOURCE_PATH) + "/test/worlds/plugins.sdf"; @@ -118,7 +119,7 @@ TEST(CmdLine, GazeboServer) } ///////////////////////////////////////////////// -TEST(CmdLine, Gazebo) +TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(Gazebo)) { std::string cmd = kIgnCommand + " -r -v 4 --iterations 5 " + std::string(PROJECT_SOURCE_PATH) + "/test/worlds/plugins.sdf"; @@ -135,7 +136,7 @@ TEST(CmdLine, Gazebo) } ///////////////////////////////////////////////// -TEST(CmdLine, ResourcePath) +TEST(CmdLine, IGN_UTILS_TEST_DISABLED_ON_WIN32(ResourcePath)) { std::string cmd = kIgnCommand + " -s -r -v 4 --iterations 1 plugins.sdf"; diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 8c8f94b32d..1b484783cf 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -69,6 +69,15 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \param[in] _req This value should be true. public: void OnDisableRecharge(const ignition::msgs::Boolean &_req); + /// \brief Callback connected to additional topics that can start battery + /// draining. + /// \param[in] _data Message data. + /// \param[in] _size Message data size. + /// \param[in] _info Information about the message. + public: void OnBatteryDrainingMsg( + const char *_data, const size_t _size, + const ignition::transport::MessageInfo &_info); + /// \brief Name of model, only used for printing warning when battery drains. public: std::string modelName; @@ -153,6 +162,9 @@ class ignition::gazebo::systems::LinearBatteryPluginPrivate /// \brief Battery state of charge message publisher public: transport::Node::Publisher statePub; + + /// \brief Whether a topic has received any battery-draining command. + public: bool startDrainingFromTopics = false; }; ///////////////////////////////////////////////// @@ -340,6 +352,23 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, << "in LinearBatteryPlugin SDF" << std::endl; } + // Subscribe to power draining topics, if any. + if (_sdf->HasElement("power_draining_topic")) + { + sdf::ElementConstPtr sdfElem = _sdf->FindElement("power_draining_topic"); + while (sdfElem) + { + const auto &topic = sdfElem->Get(); + this->dataPtr->node.SubscribeRaw(topic, + std::bind(&LinearBatteryPluginPrivate::OnBatteryDrainingMsg, + this->dataPtr.get(), std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3)); + ignmsg << "LinearBatteryPlugin subscribes to power draining topic [" + << topic << "]." << std::endl; + sdfElem = sdfElem->GetNextElement("power_draining_topic"); + } + } + ignmsg << "LinearBatteryPlugin configured. Battery name: " << this->dataPtr->battery->Name() << std::endl; igndbg << "Battery initial voltage: " << this->dataPtr->battery->InitVoltage() @@ -371,6 +400,7 @@ void LinearBatteryPluginPrivate::Reset() this->iraw = 0.0; this->ismooth = 0.0; this->q = this->q0; + this->startDrainingFromTopics = false; } ///////////////////////////////////////////////// @@ -395,13 +425,24 @@ void LinearBatteryPluginPrivate::OnDisableRecharge( this->startCharging = false; } +////////////////////////////////////////////////// +void LinearBatteryPluginPrivate::OnBatteryDrainingMsg( + const char *, const size_t, const ignition::transport::MessageInfo &) +{ + this->startDrainingFromTopics = true; +} + ////////////////////////////////////////////////// void LinearBatteryPlugin::PreUpdate( const ignition::gazebo::UpdateInfo &/*_info*/, ignition::gazebo::EntityComponentManager &_ecm) { IGN_PROFILE("LinearBatteryPlugin::PreUpdate"); - this->dataPtr->startDraining = false; + + // \todo(anyone) Add in the ability to stop the battery from draining + // after it has been started by a topic. See this comment: + // https://github.com/ignitionrobotics/ign-gazebo/pull/1255#discussion_r770223092 + this->dataPtr->startDraining = this->dataPtr->startDrainingFromTopics; // Start draining the battery if the robot has started moving if (!this->dataPtr->startDraining) { diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index 75149eef0f..e98460a15b 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -58,6 +58,11 @@ namespace systems /// (Required if `` is set to true) /// - `` True to change the battery behavior to fix some issues /// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225. + /// - `` A topic that is used to start battery + /// discharge. Any message on the specified topic will cause the batter to + /// start draining. This element can be specified multiple times if + /// multiple topics should be monitored. Note that this mechanism will + /// start the battery draining, and once started will keep drainig. class LinearBatteryPlugin : public System, public ISystemConfigure, diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index d96daf60cd..dc1bddb898 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -29,6 +29,7 @@ #include #include #include +#include #include "../../../test/helpers/EnvTestFixture.hh" #include "ignition/gazebo/EntityComponentManager.hh" @@ -92,7 +93,9 @@ class EntityFeatureMapFixture: public InternalFixture<::testing::Test> public: EnginePtrType engine; }; -TEST_F(EntityFeatureMapFixture, AddCastRemoveEntity) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(EntityFeatureMapFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(AddCastRemoveEntity)) { struct TestOptionalFeatures1 : physics::FeatureList diff --git a/test/integration/ackermann_steering_system.cc b/test/integration/ackermann_steering_system.cc index 59ea8cfbc2..3718d44069 100644 --- a/test/integration/ackermann_steering_system.cc +++ b/test/integration/ackermann_steering_system.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Model.hh" @@ -193,7 +194,8 @@ class AckermannSteeringTest }; ///////////////////////////////////////////////// -TEST_P(AckermannSteeringTest, PublishCmd) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(AckermannSteeringTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) { TestPublishCmd(common::joinPaths(std::string(PROJECT_SOURCE_PATH), "/test/worlds/ackermann_steering.sdf"), @@ -201,7 +203,8 @@ TEST_P(AckermannSteeringTest, PublishCmd) } ///////////////////////////////////////////////// -TEST_P(AckermannSteeringTest, PublishCmdCustomTopics) +TEST_P(AckermannSteeringTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmdCustomTopics)) { TestPublishCmd(common::joinPaths(std::string(PROJECT_SOURCE_PATH), "/test/worlds/ackermann_steering_custom_topics.sdf"), @@ -209,7 +212,7 @@ TEST_P(AckermannSteeringTest, PublishCmdCustomTopics) } ///////////////////////////////////////////////// -TEST_P(AckermannSteeringTest, SkidPublishCmd) +TEST_P(AckermannSteeringTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SkidPublishCmd)) { // Start server ServerConfig serverConfig; @@ -307,7 +310,7 @@ TEST_P(AckermannSteeringTest, SkidPublishCmd) } ///////////////////////////////////////////////// -TEST_P(AckermannSteeringTest, OdomFrameId) +TEST_P(AckermannSteeringTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OdomFrameId)) { // Start server ServerConfig serverConfig; @@ -365,7 +368,8 @@ TEST_P(AckermannSteeringTest, OdomFrameId) } ///////////////////////////////////////////////// -TEST_P(AckermannSteeringTest, OdomCustomFrameId) +TEST_P(AckermannSteeringTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(OdomCustomFrameId)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/air_pressure_system.cc b/test/integration/air_pressure_system.cc index 51e9000d90..2036f92041 100644 --- a/test/integration/air_pressure_system.cc +++ b/test/integration/air_pressure_system.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/components/AirPressureSensor.hh" #include "ignition/gazebo/components/Name.hh" @@ -41,7 +42,8 @@ class AirPressureTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(AirPressureTest, AirPressure) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(AirPressureTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(AirPressure)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/altimeter_system.cc b/test/integration/altimeter_system.cc index 4072d208d1..0219862050 100644 --- a/test/integration/altimeter_system.cc +++ b/test/integration/altimeter_system.cc @@ -24,6 +24,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Altimeter.hh" #include "ignition/gazebo/components/LinearVelocity.hh" @@ -59,7 +60,8 @@ void altimeterCb(const msgs::Altimeter &_msg) ///////////////////////////////////////////////// // The test checks the world pose and sensor readings of a falling altimeter -TEST_F(AltimeterTest, ModelFalling) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(AltimeterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelFalling)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/apply_joint_force_system.cc b/test/integration/apply_joint_force_system.cc index c8423e88ae..e1b28c54b9 100644 --- a/test/integration/apply_joint_force_system.cc +++ b/test/integration/apply_joint_force_system.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Joint.hh" #include "ignition/gazebo/components/Name.hh" @@ -46,7 +47,9 @@ class ApplyJointForceTestFixture : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // Tests that the ApplyJointForce accepts joint velocity commands -TEST_F(ApplyJointForceTestFixture, JointVelocityCommand) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ApplyJointForceTestFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(JointVelocityCommand)) { using namespace std::chrono_literals; diff --git a/test/integration/battery_plugin.cc b/test/integration/battery_plugin.cc index 53f09d2153..78d6ba6e77 100644 --- a/test/integration/battery_plugin.cc +++ b/test/integration/battery_plugin.cc @@ -23,6 +23,8 @@ #include #include #include +#include +#include #include #include @@ -70,8 +72,9 @@ class BatteryPluginTest : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// -// Single model consuming single battery -TEST_F(BatteryPluginTest, SingleBattery) +// Single model consuming single batter +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SingleBattery)) { const auto sdfPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "battery.sdf"); @@ -134,20 +137,107 @@ TEST_F(BatteryPluginTest, SingleBattery) EXPECT_LT(batComp->Data(), 12.592); // Check there is a single battery matching exactly the one specified - int batCount = 0; + int linearBatCount = 0; + int totalBatCount = 0; ecm->Each( [&](const Entity &_batEntity, components::BatterySoC *_batComp, components::Name *_nameComp) -> bool { - batCount++; + totalBatCount++; + if (_nameComp->Data() == "linear_battery") + { + linearBatCount++; - EXPECT_NE(kNullEntity, _batEntity); - EXPECT_EQ(_nameComp->Data(), "linear_battery"); + EXPECT_NE(kNullEntity, _batEntity); + EXPECT_EQ(_nameComp->Data(), "linear_battery"); - // Check battery component voltage data is lower than initial voltage - EXPECT_LT(_batComp->Data(), 12.592); + // Check battery component voltage data is lower than initial voltage + EXPECT_LT(_batComp->Data(), 12.592); + } return true; }); - EXPECT_EQ(batCount, 1); + EXPECT_EQ(linearBatCount, 1); + EXPECT_EQ(totalBatCount, 2); +} + +///////////////////////////////////////////////// +// Battery with power draining topics +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(BatteryPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PowerDrainTopic)) +{ + const auto sdfPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "worlds", "battery.sdf"); + sdf::Root root; + EXPECT_EQ(root.Load(sdfPath).size(), 0lu); + EXPECT_GT(root.WorldCount(), 0lu); + + ServerConfig serverConfig; + serverConfig.SetSdfFile(sdfPath); + + // A pointer to the ecm. This will be valid once we run the mock system + gazebo::EntityComponentManager *ecm = nullptr; + this->mockSystem->preUpdateCallback = + [&ecm](const gazebo::UpdateInfo &, gazebo::EntityComponentManager &_ecm) + { + ecm = &_ecm; + + // Check a battery exists + EXPECT_TRUE(ecm->HasComponentType(components::BatterySoC::typeId)); + + // Find the battery entity + Entity batEntity = ecm->EntityByComponents(components::Name( + "linear_battery_topics")); + EXPECT_NE(kNullEntity, batEntity); + + // Find the battery component + EXPECT_TRUE(ecm->EntityHasComponentType(batEntity, + components::BatterySoC::typeId)); + auto batComp = ecm->Component(batEntity); + + // Check voltage is never zero. + // This check is here to guarantee that components::BatterySoC in + // the LinearBatteryPlugin is not zero when created. If + // components::BatterySoC is zero on start, then the Physics plugin + // can disable a joint. This in turn can prevent the joint from + // rotating. See https://github.com/ignitionrobotics/ign-gazebo/issues/55 + EXPECT_GT(batComp->Data(), 0); + }; + + // Start server + Server server(serverConfig); + server.AddSystem(this->systemPtr); + server.Run(true, 100, false); + EXPECT_NE(nullptr, ecm); + + // Check a battery exists + EXPECT_TRUE(ecm->HasComponentType(components::BatterySoC::typeId)); + + // Find the battery entity + Entity batEntity = ecm->EntityByComponents(components::Name( + "linear_battery_topics")); + EXPECT_NE(kNullEntity, batEntity); + + // Find the battery component + EXPECT_TRUE(ecm->EntityHasComponentType(batEntity, + components::BatterySoC::typeId)); + auto batComp = ecm->Component(batEntity); + + // Check state of charge should be 1, since the batery has not drained + // and the is equivalent ot the . + EXPECT_DOUBLE_EQ(batComp->Data(), 1.0); + + // Send a message on one of the topics, which will + // start the battery draining when the server starts again. + ignition::transport::Node node; + auto pub = node.Advertise("/battery/discharge2"); + msgs::StringMsg msg; + pub.Publish(msg); + + // Run the server again. + server.Run(true, 100, false); + + // The state of charge should be <1, since the batery has started + // draining. + EXPECT_LT(batComp->Data(), 1.0); } diff --git a/test/integration/breadcrumbs.cc b/test/integration/breadcrumbs.cc index ed79d6eef6..17624884f4 100644 --- a/test/integration/breadcrumbs.cc +++ b/test/integration/breadcrumbs.cc @@ -29,6 +29,7 @@ #include #include #include +#include #include "ignition/gazebo/Entity.hh" #include "ignition/gazebo/Server.hh" @@ -75,7 +76,8 @@ void remainingCb(const msgs::Int32 &_msg) ///////////////////////////////////////////////// // This test checks the .../deploy/remaining topic -TEST_F(BreadcrumbsTest, Remaining) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remaining)) { // Start server this->LoadWorld("test/worlds/breadcrumbs.sdf"); @@ -133,7 +135,7 @@ TEST_F(BreadcrumbsTest, Remaining) ///////////////////////////////////////////////// // The test checks breadcrumbs are deployed at the correct pose -TEST_F(BreadcrumbsTest, DeployAtOffset) +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeployAtOffset)) { // Start server this->LoadWorld("test/worlds/breadcrumbs.sdf"); @@ -198,7 +200,7 @@ TEST_F(BreadcrumbsTest, DeployAtOffset) ///////////////////////////////////////////////// // The test checks max deployments -TEST_F(BreadcrumbsTest, MaxDeployments) +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(MaxDeployments)) { // Start server this->LoadWorld("test/worlds/breadcrumbs.sdf"); @@ -254,7 +256,7 @@ TEST_F(BreadcrumbsTest, MaxDeployments) ///////////////////////////////////////////////// // The test checks that including models from fuel works. Also checks custom // topic -TEST_F(BreadcrumbsTest, FuelDeploy) +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(FuelDeploy)) { // Start server this->LoadWorld("test/worlds/breadcrumbs.sdf"); @@ -307,7 +309,7 @@ TEST_F(BreadcrumbsTest, FuelDeploy) ///////////////////////////////////////////////// // The test checks that breadcrumbs can be performers -TEST_F(BreadcrumbsTest, Performer) +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Performer)) { // Start server this->LoadWorld("test/worlds/breadcrumbs.sdf"); @@ -381,7 +383,7 @@ TEST_F(BreadcrumbsTest, Performer) ///////////////////////////////////////////////// // Test that the volume of the performer is set when deploying a performer // breadcrumb -TEST_F(BreadcrumbsTest, PerformerSetVolume) +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PerformerSetVolume)) { // Start server this->LoadWorld("test/worlds/breadcrumbs.sdf", true); @@ -436,7 +438,7 @@ TEST_F(BreadcrumbsTest, PerformerSetVolume) ///////////////////////////////////////////////// // The test verifies breadcrumbs physics is disabled using disable_physics_time -TEST_F(BreadcrumbsTest, DeployDisablePhysics) +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeployDisablePhysics)) { // Start server this->LoadWorld("test/worlds/breadcrumbs.sdf"); @@ -514,7 +516,7 @@ TEST_F(BreadcrumbsTest, DeployDisablePhysics) ///////////////////////////////////////////////// // The test verifies that if allow_renaming is true, the Breadcrumb system // renames spawned models if a model with the same name exists. -TEST_F(BreadcrumbsTest, AllowRenaming) +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(AllowRenaming)) { // Start server this->LoadWorld("test/worlds/breadcrumbs.sdf"); @@ -568,7 +570,7 @@ std::vector ModelsByNameRegex( // The test checks that models containing Breadcrumbs can be unloaded and loaded // safely -TEST_F(BreadcrumbsTest, LevelLoadUnload) +TEST_F(BreadcrumbsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelLoadUnload)) { // Start server this->LoadWorld("test/worlds/breadcrumbs_levels.sdf", true); diff --git a/test/integration/buoyancy.cc b/test/integration/buoyancy.cc index 481c7d29ee..25ff65ba87 100644 --- a/test/integration/buoyancy.cc +++ b/test/integration/buoyancy.cc @@ -19,6 +19,7 @@ #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -42,7 +43,8 @@ class BuoyancyTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(BuoyancyTest, UniformWorldMovement) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UniformWorldMovement)) { // Start server ServerConfig serverConfig; @@ -196,7 +198,8 @@ TEST_F(BuoyancyTest, UniformWorldMovement) } ///////////////////////////////////////////////// -TEST_F(BuoyancyTest, GradedBuoyancy) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(GradedBuoyancy)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/collada_world_exporter.cc b/test/integration/collada_world_exporter.cc index 46524b5a88..a5e01fc754 100644 --- a/test/integration/collada_world_exporter.cc +++ b/test/integration/collada_world_exporter.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" @@ -50,7 +51,9 @@ class ColladaWorldExporterFixture : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(ColladaWorldExporterFixture, ExportWorld) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ColladaWorldExporterFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ExportWorld)) { this->LoadWorld(common::joinPaths("test", "worlds", "collada_world_exporter.sdf")); @@ -71,7 +74,8 @@ TEST_F(ColladaWorldExporterFixture, ExportWorld) common::removeAll("./collada_world_exporter_box_test"); } -TEST_F(ColladaWorldExporterFixture, ExportWorldFromFuelWithSubmesh) +TEST_F(ColladaWorldExporterFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ExportWorldFromFuelWithSubmesh)) { std::string world_path = ignition::common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds"); @@ -108,7 +112,8 @@ TEST_F(ColladaWorldExporterFixture, ExportWorldFromFuelWithSubmesh) common::removeAll(outputPath); } -TEST_F(ColladaWorldExporterFixture, ExportWorldMadeFromObj) +TEST_F(ColladaWorldExporterFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ExportWorldMadeFromObj)) { std::string world_path = ignition::common::joinPaths(PROJECT_SOURCE_PATH, "test", "worlds"); @@ -146,7 +151,8 @@ TEST_F(ColladaWorldExporterFixture, ExportWorldMadeFromObj) common::removeAll(outputPath); } -TEST_F(ColladaWorldExporterFixture, ExportWorldWithLights) +TEST_F(ColladaWorldExporterFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ExportWorldWithLights)) { this->LoadWorld(common::joinPaths("test", "worlds", "collada_world_exporter_lights.sdf")); diff --git a/test/integration/contact_system.cc b/test/integration/contact_system.cc index 0a9014673b..72e1f9e305 100644 --- a/test/integration/contact_system.cc +++ b/test/integration/contact_system.cc @@ -24,6 +24,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -41,7 +42,9 @@ class ContactSystemTest : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // The test checks that contacts are published by the contact system -TEST_F(ContactSystemTest, MultipleCollisionsAsContactSensors) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ContactSystemTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MultipleCollisionsAsContactSensors)) { // Start server ServerConfig serverConfig; @@ -114,7 +117,8 @@ TEST_F(ContactSystemTest, MultipleCollisionsAsContactSensors) } } -TEST_F(ContactSystemTest, RemoveContactSensor) +TEST_F(ContactSystemTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(RemoveContactSensor)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/detachable_joint.cc b/test/integration/detachable_joint.cc index bbbe91c66f..02005b0ae0 100644 --- a/test/integration/detachable_joint.cc +++ b/test/integration/detachable_joint.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include "ignition/gazebo/Link.hh" #include "ignition/gazebo/Server.hh" @@ -57,7 +58,8 @@ class DetachableJointTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(DetachableJointTest, StartConnected) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(DetachableJointTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StartConnected)) { using namespace std::chrono_literals; @@ -135,7 +137,7 @@ TEST_F(DetachableJointTest, StartConnected) } ///////////////////////////////////////////////// -TEST_F(DetachableJointTest, LinksInSameModel) +TEST_F(DetachableJointTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LinksInSameModel)) { using namespace std::chrono_literals; diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index e3a0081fa5..507369ff42 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Model.hh" @@ -210,7 +211,8 @@ class DiffDriveTest : public InternalFixture<::testing::TestWithParam> }; ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, PublishCmd) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) { TestPublishCmd( std::string(PROJECT_SOURCE_PATH) + "/test/worlds/diff_drive.sdf", @@ -218,7 +220,7 @@ TEST_P(DiffDriveTest, PublishCmd) } ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, PublishCmdCustomTopics) +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmdCustomTopics)) { TestPublishCmd( std::string(PROJECT_SOURCE_PATH) + @@ -227,7 +229,7 @@ TEST_P(DiffDriveTest, PublishCmdCustomTopics) } ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, SkidPublishCmd) +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SkidPublishCmd)) { // Start server ServerConfig serverConfig; @@ -329,7 +331,7 @@ TEST_P(DiffDriveTest, SkidPublishCmd) } ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, EnableDisableCmd) +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(EnableDisableCmd)) { // Start server ServerConfig serverConfig; @@ -453,7 +455,7 @@ TEST_P(DiffDriveTest, EnableDisableCmd) } ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, OdomFrameId) +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OdomFrameId)) { // Start server ServerConfig serverConfig; @@ -511,7 +513,7 @@ TEST_P(DiffDriveTest, OdomFrameId) } ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, OdomCustomFrameId) +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OdomCustomFrameId)) { // Start server ServerConfig serverConfig; @@ -568,7 +570,7 @@ TEST_P(DiffDriveTest, OdomCustomFrameId) } ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, Pose_VFrameId) +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Pose_VFrameId)) { // Start server ServerConfig serverConfig; @@ -628,7 +630,7 @@ TEST_P(DiffDriveTest, Pose_VFrameId) } ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, Pose_VCustomFrameId) +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Pose_VCustomFrameId)) { // Start server ServerConfig serverConfig; @@ -688,7 +690,7 @@ TEST_P(DiffDriveTest, Pose_VCustomFrameId) } ///////////////////////////////////////////////// -TEST_P(DiffDriveTest, Pose_VCustomTfTopic) +TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Pose_VCustomTfTopic)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/each_new_removed.cc b/test/integration/each_new_removed.cc index 780e210250..353b4080bc 100644 --- a/test/integration/each_new_removed.cc +++ b/test/integration/each_new_removed.cc @@ -22,6 +22,7 @@ #include #include +#include #include #include "ignition/gazebo/components/Factory.hh" @@ -44,7 +45,9 @@ class EachNewRemovedFixture : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(EachNewRemovedFixture, EachNewEachRemovedInSystem) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(EachNewRemovedFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EachNewEachRemovedInSystem)) { ignition::gazebo::ServerConfig serverConfig; diff --git a/test/integration/entity_erase.cc b/test/integration/entity_erase.cc index a4ec941fdb..7bab7a0908 100644 --- a/test/integration/entity_erase.cc +++ b/test/integration/entity_erase.cc @@ -19,6 +19,8 @@ #include +#include + #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) #include "../helpers/EnvTestFixture.hh" @@ -32,7 +34,9 @@ class PhysicsSystemFixture : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(PhysicsSystemFixture, CreatePhysicsWorld) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(CreatePhysicsWorld)) { ignition::gazebo::ServerConfig serverConfig; diff --git a/test/integration/events.cc b/test/integration/events.cc index b71fb4de52..e3bd2072a2 100644 --- a/test/integration/events.cc +++ b/test/integration/events.cc @@ -18,6 +18,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -34,7 +35,8 @@ class EventTrigger : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(EventTrigger, TriggerPause) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(EventTrigger, IGN_UTILS_TEST_DISABLED_ON_WIN32(TriggerPause)) { // Create server ServerConfig config; diff --git a/test/integration/examples_build.cc b/test/integration/examples_build.cc index 55e3ef99f3..c6376de6cb 100644 --- a/test/integration/examples_build.cc +++ b/test/integration/examples_build.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/test_config.hh" #include "../helpers/EnvTestFixture.hh" @@ -182,7 +183,8 @@ void ExamplesBuild::Build(const std::string &_type) } ////////////////////////////////////////////////// -TEST_P(ExamplesBuild, Build) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(ExamplesBuild, IGN_UTILS_TEST_DISABLED_ON_WIN32(Build)) { Build(GetParam()); } diff --git a/test/integration/follow_actor_system.cc b/test/integration/follow_actor_system.cc index 4b183154bf..befc3b2d2e 100644 --- a/test/integration/follow_actor_system.cc +++ b/test/integration/follow_actor_system.cc @@ -84,7 +84,9 @@ class Relay ///////////////////////////////////////////////// -TEST_P(FollowActorTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PublishCmd)) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(FollowActorTest, + IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PublishCmd)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/halt_motion.cc b/test/integration/halt_motion.cc index 2564e1513b..fe8e0d8a92 100644 --- a/test/integration/halt_motion.cc +++ b/test/integration/halt_motion.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Model.hh" @@ -147,7 +148,8 @@ class HaltMotionTest : public InternalFixture<::testing::TestWithParam> }; ///////////////////////////////////////////////// -TEST_P(HaltMotionTest, PublishCmd) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(HaltMotionTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) { TestPublishCmd( std::string(PROJECT_SOURCE_PATH) + "/test/worlds/diff_drive.sdf", diff --git a/test/integration/imu_system.cc b/test/integration/imu_system.cc index 3cdd522c8e..388da45bae 100644 --- a/test/integration/imu_system.cc +++ b/test/integration/imu_system.cc @@ -23,6 +23,7 @@ #include #include #include +#include #include "ignition/gazebo/components/AngularVelocity.hh" #include "ignition/gazebo/components/Gravity.hh" @@ -62,7 +63,8 @@ void imuCb(const msgs::IMU &_msg) ///////////////////////////////////////////////// // The test checks the world pose and sensor readings of a falling imu -TEST_F(ImuTest, ModelFalling) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ImuTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelFalling)) { double z = 3; // TODO(anyone): get step size from sdf @@ -209,7 +211,7 @@ TEST_F(ImuTest, ModelFalling) ///////////////////////////////////////////////// // The test checks to make sure orientation is not published if it is deabled -TEST_F(ImuTest, OrientationDisabled) +TEST_F(ImuTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OrientationDisabled)) { imuMsgs.clear(); diff --git a/test/integration/joint_controller_system.cc b/test/integration/joint_controller_system.cc index 362152efda..f14a798f73 100644 --- a/test/integration/joint_controller_system.cc +++ b/test/integration/joint_controller_system.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/components/AngularVelocity.hh" #include "ignition/gazebo/components/Link.hh" @@ -46,7 +47,9 @@ class JointControllerTestFixture : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // Tests that the JointController accepts joint velocity commands -TEST_F(JointControllerTestFixture, JointVelocityCommand) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(JointControllerTestFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(JointVelocityCommand)) { using namespace std::chrono_literals; @@ -143,7 +146,8 @@ TEST_F(JointControllerTestFixture, JointVelocityCommand) ///////////////////////////////////////////////// // Tests the JointController using joint force commands -TEST_F(JointControllerTestFixture, JointVelocityCommandWithForce) +TEST_F(JointControllerTestFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(JointVelocityCommandWithForce)) { using namespace std::chrono_literals; diff --git a/test/integration/joint_position_controller_system.cc b/test/integration/joint_position_controller_system.cc index 5b93173f4a..1068c21174 100644 --- a/test/integration/joint_position_controller_system.cc +++ b/test/integration/joint_position_controller_system.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Joint.hh" #include "ignition/gazebo/components/JointPosition.hh" @@ -47,7 +48,9 @@ class JointPositionControllerTestFixture ///////////////////////////////////////////////// // Tests that the JointPositionController accepts joint position commands -TEST_F(JointPositionControllerTestFixture, JointPositionForceCommand) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(JointPositionControllerTestFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(JointPositionForceCommand)) { using namespace std::chrono_literals; @@ -123,7 +126,8 @@ TEST_F(JointPositionControllerTestFixture, JointPositionForceCommand) ///////////////////////////////////////////////// // Tests that the JointPositionController accepts joint position commands -TEST_F(JointPositionControllerTestFixture, JointPositonVelocityCommand) +TEST_F(JointPositionControllerTestFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(JointPositonVelocityCommand)) { using namespace std::chrono_literals; diff --git a/test/integration/joint_state_publisher_system.cc b/test/integration/joint_state_publisher_system.cc index d58e59c522..d5cb4a090e 100644 --- a/test/integration/joint_state_publisher_system.cc +++ b/test/integration/joint_state_publisher_system.cc @@ -19,6 +19,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" @@ -35,7 +36,9 @@ class JointStatePublisherTest }; ///////////////////////////////////////////////// -TEST_F(JointStatePublisherTest, DefaultPublisher) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(JointStatePublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultPublisher)) { // Start server ServerConfig serverConfig; @@ -86,7 +89,8 @@ TEST_F(JointStatePublisherTest, DefaultPublisher) } ///////////////////////////////////////////////// -TEST_F(JointStatePublisherTest, LimitedPublisher) +TEST_F(JointStatePublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LimitedPublisher)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/joint_trajectory_controller_system.cc b/test/integration/joint_trajectory_controller_system.cc index 4bfb04faf8..160af92aac 100644 --- a/test/integration/joint_trajectory_controller_system.cc +++ b/test/integration/joint_trajectory_controller_system.cc @@ -25,6 +25,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Joint.hh" #include "ignition/gazebo/components/JointPosition.hh" @@ -52,8 +53,9 @@ class JointTrajectoryControllerTestFixture ///////////////////////////////////////////////// // Tests that JointTrajectoryController accepts position-controlled joint // trajectory +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 TEST_F(JointTrajectoryControllerTestFixture, - JointTrajectoryControllerPositionControl) + IGN_UTILS_TEST_DISABLED_ON_WIN32(JointTrajectoryControllerPositionControl)) { using namespace std::chrono_literals; @@ -229,7 +231,7 @@ TEST_F(JointTrajectoryControllerTestFixture, // Tests that JointTrajectoryController accepts velocity-controlled joint // trajectory TEST_F(JointTrajectoryControllerTestFixture, - JointTrajectoryControllerVelocityControl) + IGN_UTILS_TEST_DISABLED_ON_WIN32(JointTrajectoryControllerVelocityControl)) { using namespace std::chrono_literals; diff --git a/test/integration/kinetic_energy_monitor_system.cc b/test/integration/kinetic_energy_monitor_system.cc index 20a36919a2..8fcddcb394 100644 --- a/test/integration/kinetic_energy_monitor_system.cc +++ b/test/integration/kinetic_energy_monitor_system.cc @@ -24,6 +24,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -51,7 +52,8 @@ void cb(const msgs::Double &_msg) ///////////////////////////////////////////////// // The test checks the world pose and sensor readings of a falling altimeter -TEST_F(KineticEnergyMonitorTest, ModelFalling) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(KineticEnergyMonitorTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelFalling)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/level_manager.cc b/test/integration/level_manager.cc index f9c7e364d6..56a35e91ad 100644 --- a/test/integration/level_manager.cc +++ b/test/integration/level_manager.cc @@ -23,6 +23,7 @@ #include #include +#include #include #include #include @@ -178,7 +179,8 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// /// Check default level includes entities not included by other levels -TEST_F(LevelManagerFixture, DefaultLevel) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultLevel)) { std::vector> levelEntityNamesList; @@ -224,7 +226,7 @@ TEST_F(LevelManagerFixture, DefaultLevel) /////////////////////////////////////////////// /// Check a level is loaded when a performer is inside a level /// Check a level is unloaded when a performer is outside a level -TEST_F(LevelManagerFixture, LevelLoadUnload) +TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelLoadUnload)) { ModelMover perf1(*this->server->EntityByName("sphere")); this->server->AddSystem(perf1.systemPtr); @@ -274,7 +276,7 @@ TEST_F(LevelManagerFixture, LevelLoadUnload) /////////////////////////////////////////////// /// Check behaviour of level buffers -TEST_F(LevelManagerFixture, LevelBuffers) +TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelBuffers)) { ModelMover perf1(*this->server->EntityByName("sphere")); this->server->AddSystem(perf1.systemPtr); @@ -312,7 +314,8 @@ TEST_F(LevelManagerFixture, LevelBuffers) /////////////////////////////////////////////// /// Check that multiple performers can load/unload multiple levels independently -TEST_F(LevelManagerFixture, LevelsWithMultiplePerformers) +TEST_F(LevelManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelsWithMultiplePerformers)) { ModelMover perf1(*this->server->EntityByName("sphere")); ModelMover perf2(*this->server->EntityByName("box")); @@ -429,7 +432,8 @@ TEST_F(LevelManagerFixture, LevelsWithMultiplePerformers) /////////////////////////////////////////////// /// Check that buffers work properly with multiple performers -TEST_F(LevelManagerFixture, LevelBuffersWithMultiplePerformers) +TEST_F(LevelManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelBuffersWithMultiplePerformers)) { ModelMover perf1(*this->server->EntityByName("sphere")); ModelMover perf2(*this->server->EntityByName("box")); diff --git a/test/integration/level_manager_runtime_performers.cc b/test/integration/level_manager_runtime_performers.cc index cb1ffedeb6..68ef368ee7 100644 --- a/test/integration/level_manager_runtime_performers.cc +++ b/test/integration/level_manager_runtime_performers.cc @@ -26,6 +26,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -206,7 +207,8 @@ class LevelManagerFixture : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// /// Check default level includes entities not included by other levels -TEST_F(LevelManagerFixture, DefaultLevel) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultLevel)) { std::vector> levelEntityNamesList; @@ -252,7 +254,7 @@ TEST_F(LevelManagerFixture, DefaultLevel) /////////////////////////////////////////////// /// Check a level is loaded when a performer is inside a level /// Check a level is unloaded when a performer is outside a level -TEST_F(LevelManagerFixture, LevelLoadUnload) +TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelLoadUnload)) { ModelMover perf1(*this->server->EntityByName("sphere")); this->server->AddSystem(perf1.systemPtr); @@ -302,7 +304,7 @@ TEST_F(LevelManagerFixture, LevelLoadUnload) /////////////////////////////////////////////// /// Check behaviour of level buffers -TEST_F(LevelManagerFixture, LevelBuffers) +TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelBuffers)) { ModelMover perf1(*this->server->EntityByName("sphere")); this->server->AddSystem(perf1.systemPtr); @@ -340,7 +342,8 @@ TEST_F(LevelManagerFixture, LevelBuffers) /////////////////////////////////////////////// /// Check that multiple performers can load/unload multiple levels independently -TEST_F(LevelManagerFixture, LevelsWithMultiplePerformers) +TEST_F(LevelManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelsWithMultiplePerformers)) { ModelMover perf1(*this->server->EntityByName("sphere")); ModelMover perf2(*this->server->EntityByName("box")); @@ -457,7 +460,8 @@ TEST_F(LevelManagerFixture, LevelsWithMultiplePerformers) /////////////////////////////////////////////// /// Check that buffers work properly with multiple performers -TEST_F(LevelManagerFixture, LevelBuffersWithMultiplePerformers) +TEST_F(LevelManagerFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelBuffersWithMultiplePerformers)) { ModelMover perf1(*this->server->EntityByName("sphere")); ModelMover perf2(*this->server->EntityByName("box")); diff --git a/test/integration/lift_drag_system.cc b/test/integration/lift_drag_system.cc index 0865a4fcc1..75d1b2ddc2 100644 --- a/test/integration/lift_drag_system.cc +++ b/test/integration/lift_drag_system.cc @@ -24,6 +24,7 @@ #include #include #include +#include #include "ignition/gazebo/components/AngularVelocity.hh" #include "ignition/gazebo/components/Joint.hh" @@ -69,7 +70,9 @@ class VerticalForceParamFixture ///////////////////////////////////////////////// /// Measure / verify force torques against analytical answers. -TEST_P(VerticalForceParamFixture, VerifyVerticalForce) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(VerticalForceParamFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(VerifyVerticalForce)) { using namespace std::chrono_literals; ignition::common::setenv( diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 2d920f043b..975def19dd 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -37,6 +37,7 @@ #include #include #include +#include #include #include @@ -262,7 +263,8 @@ class LogSystemTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogPlaybackStatistics) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogPlaybackStatistics)) { // TODO(anyone) see LogSystemTest.LogControl comment about re-recording auto logPath = common::joinPaths(PROJECT_SOURCE_PATH, "test", "media", @@ -314,7 +316,7 @@ TEST_F(LogSystemTest, LogPlaybackStatistics) ///////////////////////////////////////////////// // Logging behavior when no paths are specified -TEST_F(LogSystemTest, LogDefaults) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogDefaults)) { // Create temp directory to store log this->CreateLogsDir(); @@ -418,7 +420,7 @@ TEST_F(LogSystemTest, LogDefaults) ///////////////////////////////////////////////// // Logging behavior when a path is specified either via the C++ API, SDF, or // the command line. -TEST_F(LogSystemTest, LogPaths) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogPaths)) { // Create temp directory to store log this->CreateLogsDir(); @@ -687,7 +689,7 @@ TEST_F(LogSystemTest, LogPaths) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, RecordAndPlayback) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RecordAndPlayback)) { // Create temp directory to store log this->CreateLogsDir(); @@ -837,7 +839,7 @@ TEST_F(LogSystemTest, RecordAndPlayback) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogControl) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogControl)) { // TODO(anyone) when re-recording state.tlog file, do not run // `ign gazebo --record rolling_shapes.sdf` with `-r` flag and pause sim @@ -957,7 +959,7 @@ TEST_F(LogSystemTest, LogControl) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogOverwrite) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogOverwrite)) { // Create temp directory to store log this->CreateLogsDir(); @@ -1106,7 +1108,7 @@ TEST_F(LogSystemTest, LogOverwrite) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogControlLevels) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogControlLevels)) { auto logPath = common::joinPaths(PROJECT_SOURCE_PATH, "test", "media", "levels_log"); @@ -1245,7 +1247,7 @@ TEST_F(LogSystemTest, LogControlLevels) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogCompress) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogCompress)) { // Create temp directory to store log this->CreateLogsDir(); @@ -1351,7 +1353,7 @@ TEST_F(LogSystemTest, LogCompress) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogCompressOverwrite) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogCompressOverwrite)) { // Create temp directory to store log this->CreateLogsDir(); @@ -1397,7 +1399,7 @@ TEST_F(LogSystemTest, LogCompressOverwrite) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogCompressCmdLine) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogCompressCmdLine)) { #ifndef __APPLE__ // Create temp directory to store log @@ -1477,7 +1479,7 @@ TEST_F(LogSystemTest, LogCompressCmdLine) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogResources) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogResources)) { // Create temp directory to store log this->CreateLogsDir(); @@ -1564,7 +1566,7 @@ TEST_F(LogSystemTest, LogResources) } ///////////////////////////////////////////////// -TEST_F(LogSystemTest, LogTopics) +TEST_F(LogSystemTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogTopics)) { // Create temp directory to store log this->CreateLogsDir(); diff --git a/test/integration/logical_audio_sensor_plugin.cc b/test/integration/logical_audio_sensor_plugin.cc index 0d403402f0..b8c8be6fba 100644 --- a/test/integration/logical_audio_sensor_plugin.cc +++ b/test/integration/logical_audio_sensor_plugin.cc @@ -28,6 +28,7 @@ #include #include #include +#include #include "ignition/gazebo/components/LogicalAudio.hh" #include "ignition/gazebo/components/Pose.hh" @@ -49,7 +50,9 @@ class LogicalAudioTest : public InternalFixture<::testing::Test> { }; -TEST_F(LogicalAudioTest, LogicalAudioDetections) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(LogicalAudioTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(LogicalAudioDetections)) { ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + @@ -204,7 +207,7 @@ TEST_F(LogicalAudioTest, LogicalAudioDetections) "world/logical_audio_sensor/model/source_model/sensor/source_1"); } -TEST_F(LogicalAudioTest, LogicalAudioServices) +TEST_F(LogicalAudioTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogicalAudioServices)) { ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + diff --git a/test/integration/logical_camera_system.cc b/test/integration/logical_camera_system.cc index 09c96f3a46..e87306172d 100644 --- a/test/integration/logical_camera_system.cc +++ b/test/integration/logical_camera_system.cc @@ -23,6 +23,7 @@ #include #include #include +#include #include "ignition/gazebo/components/LogicalCamera.hh" #include "ignition/gazebo/components/Model.hh" @@ -66,7 +67,8 @@ void logicalCamera2Cb(const msgs::LogicalCameraImage &_msg) ///////////////////////////////////////////////// // This test checks that both logical cameras in the world can see a box // at the correct relative pose. -TEST_F(LogicalCameraTest, LogicalCameraBox) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(LogicalCameraTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogicalCameraBox)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/magnetometer_system.cc b/test/integration/magnetometer_system.cc index cf29f976f8..1b3b53464e 100644 --- a/test/integration/magnetometer_system.cc +++ b/test/integration/magnetometer_system.cc @@ -23,6 +23,7 @@ #include #include #include +#include #include "ignition/gazebo/components/MagneticField.hh" #include "ignition/gazebo/components/Magnetometer.hh" @@ -60,7 +61,8 @@ void magnetometerCb(const msgs::Magnetometer &_msg) ///////////////////////////////////////////////// // The test checks the detected field from a rotated magnetometer -TEST_F(MagnetometerTest, RotatedMagnetometer) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(MagnetometerTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RotatedMagnetometer)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/multicopter.cc b/test/integration/multicopter.cc index f88789a531..6062e84630 100644 --- a/test/integration/multicopter.cc +++ b/test/integration/multicopter.cc @@ -25,6 +25,7 @@ #include #include #include +#include #include "ignition/gazebo/components/AngularVelocity.hh" #include "ignition/gazebo/components/Joint.hh" @@ -66,7 +67,8 @@ class MulticopterTest : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // Test that commanded motor speed is applied -TEST_F(MulticopterTest, CommandedMotorSpeed) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(MulticopterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(CommandedMotorSpeed)) { // Start server auto server = this->StartServer("/test/worlds/quadcopter.sdf"); @@ -132,7 +134,8 @@ TEST_F(MulticopterTest, CommandedMotorSpeed) } ///////////////////////////////////////////////// -TEST_F(MulticopterTest, MulticopterVelocityControl) +TEST_F(MulticopterTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MulticopterVelocityControl)) { // Start server auto server = @@ -240,7 +243,8 @@ TEST_F(MulticopterTest, MulticopterVelocityControl) ///////////////////////////////////////////////// // Test the interactions between MulticopterVelocityControl and // MulticopterMotorModel -TEST_F(MulticopterTest, ModelAndVelocityControlInteraction) +TEST_F(MulticopterTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelAndVelocityControlInteraction)) { // Start server auto server = diff --git a/test/integration/nested_model_physics.cc b/test/integration/nested_model_physics.cc index 21372e1f09..f3eeb33e02 100644 --- a/test/integration/nested_model_physics.cc +++ b/test/integration/nested_model_physics.cc @@ -18,6 +18,7 @@ #include #include +#include #include "ignition/math/Pose3.hh" #include "ignition/gazebo/Server.hh" @@ -41,7 +42,8 @@ class NestedModelPhysicsTest : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// /// Test that a tower of 3 boxes built with an and further nesting /// moves appropriately with joints in dartsim -TEST_F(NestedModelPhysicsTest, Movement) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(NestedModelPhysicsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Movement)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/network_handshake.cc b/test/integration/network_handshake.cc index 09b349e002..11d42da572 100644 --- a/test/integration/network_handshake.cc +++ b/test/integration/network_handshake.cc @@ -19,6 +19,8 @@ #include #include +#include + #include "ignition/msgs/world_control.pb.h" #include "ignition/msgs/world_stats.pb.h" #include "ignition/transport/Node.hh" @@ -66,7 +68,8 @@ class NetworkHandshake : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(NetworkHandshake, Handshake) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(NetworkHandshake, IGN_UTILS_TEST_DISABLED_ON_WIN32(Handshake)) { ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); @@ -122,7 +125,7 @@ TEST_F(NetworkHandshake, Handshake) } ///////////////////////////////////////////////// -TEST_F(NetworkHandshake, Updates) +TEST_F(NetworkHandshake, IGN_UTILS_TEST_DISABLED_ON_WIN32(Updates)) { auto pluginElem = std::make_shared(); pluginElem->SetName("plugin"); diff --git a/test/integration/odometry_publisher.cc b/test/integration/odometry_publisher.cc index e918d2885e..c60e19588e 100644 --- a/test/integration/odometry_publisher.cc +++ b/test/integration/odometry_publisher.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include "ignition/gazebo/components/AngularVelocity.hh" #include "ignition/gazebo/components/AngularVelocityCmd.hh" @@ -396,7 +397,8 @@ class OdometryPublisherTest }; ///////////////////////////////////////////////// -TEST_P(OdometryPublisherTest, Movement) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(OdometryPublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Movement)) { TestMovement( std::string(PROJECT_SOURCE_PATH) + "/test/worlds/odometry_publisher.sdf", @@ -404,7 +406,8 @@ TEST_P(OdometryPublisherTest, Movement) } ///////////////////////////////////////////////// -TEST_P(OdometryPublisherTest, MovementCustomTopic) +TEST_P(OdometryPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MovementCustomTopic)) { TestMovement( std::string(PROJECT_SOURCE_PATH) + @@ -413,7 +416,7 @@ TEST_P(OdometryPublisherTest, MovementCustomTopic) } ///////////////////////////////////////////////// -TEST_P(OdometryPublisherTest, Movement3d) +TEST_P(OdometryPublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Movement3d)) { TestMovement3d( ignition::common::joinPaths(PROJECT_SOURCE_PATH, @@ -422,7 +425,7 @@ TEST_P(OdometryPublisherTest, Movement3d) } ///////////////////////////////////////////////// -TEST_P(OdometryPublisherTest, OdomFrameId) +TEST_P(OdometryPublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OdomFrameId)) { TestPublishCmd( std::string(PROJECT_SOURCE_PATH) + "/test/worlds/odometry_publisher.sdf", @@ -432,7 +435,8 @@ TEST_P(OdometryPublisherTest, OdomFrameId) } ///////////////////////////////////////////////// -TEST_P(OdometryPublisherTest, OdomCustomFrameId) +TEST_P(OdometryPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(OdomCustomFrameId)) { TestPublishCmd( std::string(PROJECT_SOURCE_PATH) + diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index 0b95df9432..40bb5308d1 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -23,6 +23,7 @@ #include #include +#include #include "ignition/gazebo/Entity.hh" #include "ignition/gazebo/Server.hh" @@ -59,7 +60,8 @@ class ParticleEmitterTest : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // Load an SDF with a particle emitter and verify its properties. -TEST_F(ParticleEmitterTest, SDFLoad) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ParticleEmitterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDFLoad)) { bool updateCustomChecked{false}; bool updateDefaultChecked{false}; diff --git a/test/integration/particle_emitter2.cc b/test/integration/particle_emitter2.cc index d8b4922c7b..4d71f3349a 100644 --- a/test/integration/particle_emitter2.cc +++ b/test/integration/particle_emitter2.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/Entity.hh" #include "ignition/gazebo/Server.hh" @@ -58,7 +59,8 @@ class ParticleEmitter2Test : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // Load an SDF with a particle emitter and verify its properties. -TEST_F(ParticleEmitter2Test, SDFLoad) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ParticleEmitter2Test, IGN_UTILS_TEST_DISABLED_ON_WIN32(SDFLoad)) { bool updateCustomChecked{false}; bool updateDefaultChecked{false}; diff --git a/test/integration/performer_detector.cc b/test/integration/performer_detector.cc index e5501099ab..0ae453d25c 100644 --- a/test/integration/performer_detector.cc +++ b/test/integration/performer_detector.cc @@ -19,6 +19,7 @@ #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -60,7 +61,8 @@ class PerformerDetectorTest : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // Test that commanded motor speed is applied -TEST_F(PerformerDetectorTest, MovingPerformer) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(PerformerDetectorTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(MovingPerformer)) { auto server = this->StartServer("/test/worlds/performer_detector.sdf"); @@ -191,7 +193,8 @@ TEST_F(PerformerDetectorTest, MovingPerformer) ///////////////////////////////////////////////// // Test that Performer detector handles the case where the associated model is // removed, for example, by the level manager -TEST_F(PerformerDetectorTest, HandlesRemovedParentModel) +TEST_F(PerformerDetectorTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(HandlesRemovedParentModel)) { auto server = this->StartServer("/test/worlds/performer_detector.sdf", true); diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index cb21e18454..2941fc898f 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -27,6 +27,7 @@ #include #include #include +#include #include #include #include @@ -117,8 +118,9 @@ TEST_F(PhysicsSystemFixture, CreatePhysicsWorld) // TODO(addisu) add useful EXPECT calls } -///////////////////////////////////////////////// -TEST_F(PhysicsSystemFixture, FallingObject) +//////////////////////////////////////////////// +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(FallingObject)) { ignition::gazebo::ServerConfig serverConfig; @@ -187,7 +189,7 @@ TEST_F(PhysicsSystemFixture, FallingObject) // This tests whether links with fixed joints keep their relative transforms // after physics. For that to work properly, the canonical link implementation // must be correct. -TEST_F(PhysicsSystemFixture, CanonicalLink) +TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CanonicalLink)) { ignition::gazebo::ServerConfig serverConfig; @@ -258,7 +260,8 @@ TEST_F(PhysicsSystemFixture, CanonicalLink) ///////////////////////////////////////////////// // Same as the CanonicalLink test, but with a non-default canonical link -TEST_F(PhysicsSystemFixture, NonDefaultCanonicalLink) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(NonDefaultCanonicalLink)) { ignition::gazebo::ServerConfig serverConfig; @@ -313,7 +316,7 @@ TEST_F(PhysicsSystemFixture, NonDefaultCanonicalLink) ///////////////////////////////////////////////// // Test physics integration with revolute joints -TEST_F(PhysicsSystemFixture, RevoluteJoint) +TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(RevoluteJoint)) { ignition::gazebo::ServerConfig serverConfig; @@ -392,7 +395,7 @@ TEST_F(PhysicsSystemFixture, RevoluteJoint) } ///////////////////////////////////////////////// -TEST_F(PhysicsSystemFixture, CreateRuntime) +TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(CreateRuntime)) { ignition::gazebo::ServerConfig serverConfig; gazebo::Server server(serverConfig); @@ -475,7 +478,8 @@ TEST_F(PhysicsSystemFixture, CreateRuntime) } ///////////////////////////////////////////////// -TEST_F(PhysicsSystemFixture, SetFrictionCoefficient) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SetFrictionCoefficient)) { ignition::gazebo::ServerConfig serverConfig; @@ -560,7 +564,8 @@ TEST_F(PhysicsSystemFixture, SetFrictionCoefficient) ///////////////////////////////////////////////// /// Test that joint position reported by the physics system include all axes -TEST_F(PhysicsSystemFixture, MultiAxisJointPosition) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MultiAxisJointPosition)) { ignition::gazebo::ServerConfig serverConfig; @@ -639,7 +644,8 @@ TEST_F(PhysicsSystemFixture, MultiAxisJointPosition) ///////////////////////////////////////////////// /// Test joint position reset component -TEST_F(PhysicsSystemFixture, ResetPositionComponent) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ResetPositionComponent)) { ignition::gazebo::ServerConfig serverConfig; @@ -738,7 +744,8 @@ TEST_F(PhysicsSystemFixture, ResetPositionComponent) ///////////////////////////////////////////////// /// Test joint veocity reset component -TEST_F(PhysicsSystemFixture, ResetVelocityComponent) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ResetVelocityComponent)) { ignition::gazebo::ServerConfig serverConfig; @@ -1210,7 +1217,7 @@ TEST_F(PhysicsSystemFixtureWithDart6_10, JointEffortLimitsCommandComponent) } ///////////////////////////////////////////////// -TEST_F(PhysicsSystemFixture, GetBoundingBox) +TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(GetBoundingBox)) { ignition::gazebo::ServerConfig serverConfig; @@ -1281,7 +1288,7 @@ TEST_F(PhysicsSystemFixture, GetBoundingBox) ///////////////////////////////////////////////// // This tests whether nested models can be loaded correctly -TEST_F(PhysicsSystemFixture, NestedModel) +TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModel)) { ignition::gazebo::ServerConfig serverConfig; @@ -1386,7 +1393,8 @@ TEST_F(PhysicsSystemFixture, NestedModel) } // This tests whether nested models can be loaded correctly -TEST_F(PhysicsSystemFixture, IncludeNestedModelDartsim) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(IncludeNestedModelDartsim)) { std::string path = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models"; ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", path.c_str()); @@ -1528,7 +1536,8 @@ TEST_F(PhysicsSystemFixture, IncludeNestedModelDartsim) } // This tests whether nested models can be loaded correctly -TEST_F(PhysicsSystemFixture, IncludeNestedModelTPE) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(IncludeNestedModelTPE)) { std::string path = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models"; ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", path.c_str()); @@ -1670,7 +1679,8 @@ TEST_F(PhysicsSystemFixture, IncludeNestedModelTPE) } // This tests whether the poses of nested models are updated correctly -TEST_F(PhysicsSystemFixture, NestedModelIndividualCanonicalLinks) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModelIndividualCanonicalLinks)) { ignition::gazebo::ServerConfig serverConfig; @@ -1771,7 +1781,8 @@ TEST_F(PhysicsSystemFixture, NestedModelIndividualCanonicalLinks) } ///////////////////////////////////////////////// -TEST_F(PhysicsSystemFixture, DefaultPhysicsOptions) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultPhysicsOptions)) { ignition::gazebo::ServerConfig serverConfig; @@ -1857,7 +1868,8 @@ TEST_F(PhysicsSystemFixture, PhysicsOptions) ///////////////////////////////////////////////// // This tests whether pose updates are correct for a model whose canonical link // changes, but other links do not -TEST_F(PhysicsSystemFixture, MovingCanonicalLinkOnly) +TEST_F(PhysicsSystemFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MovingCanonicalLinkOnly)) { ignition::gazebo::ServerConfig serverConfig; @@ -1984,7 +1996,7 @@ TEST_F(PhysicsSystemFixture, MovingCanonicalLinkOnly) } ///////////////////////////////////////////////// -TEST_F(PhysicsSystemFixture, Heightmap) +TEST_F(PhysicsSystemFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(Heightmap)) { ignition::gazebo::ServerConfig serverConfig; diff --git a/test/integration/pose_publisher_system.cc b/test/integration/pose_publisher_system.cc index 687090cdee..0a1a19f3d6 100644 --- a/test/integration/pose_publisher_system.cc +++ b/test/integration/pose_publisher_system.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Model.hh" @@ -98,7 +99,8 @@ std::string addDelimiter(const std::vector &_name, } ///////////////////////////////////////////////// -TEST_F(PosePublisherTest, PublishCmd) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) { // Start server ServerConfig serverConfig; @@ -320,7 +322,7 @@ TEST_F(PosePublisherTest, PublishCmd) } ///////////////////////////////////////////////// -TEST_F(PosePublisherTest, UpdateFrequency) +TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UpdateFrequency)) { // Start server ServerConfig serverConfig; @@ -385,7 +387,7 @@ TEST_F(PosePublisherTest, UpdateFrequency) } ///////////////////////////////////////////////// -TEST_F(PosePublisherTest, StaticPosePublisher) +TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StaticPosePublisher)) { // Start server ServerConfig serverConfig; @@ -641,7 +643,8 @@ TEST_F(PosePublisherTest, StaticPosePublisher) } ///////////////////////////////////////////////// -TEST_F(PosePublisherTest, StaticPoseUpdateFrequency) +TEST_F(PosePublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(StaticPoseUpdateFrequency)) { // Start server ServerConfig serverConfig; @@ -708,7 +711,8 @@ TEST_F(PosePublisherTest, StaticPoseUpdateFrequency) } ///////////////////////////////////////////////// -TEST_F(PosePublisherTest, NestedModelLoadPlugin) +TEST_F(PosePublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(NestedModelLoadPlugin)) { // Start server ServerConfig serverConfig; diff --git a/test/integration/save_world.cc b/test/integration/save_world.cc index 0e3964b052..329182edea 100644 --- a/test/integration/save_world.cc +++ b/test/integration/save_world.cc @@ -87,7 +87,9 @@ class SdfGeneratorFixture : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(SdfGeneratorFixture, WorldWithModelsSpawnedAfterLoad) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(SdfGeneratorFixture, + IGN_UTILS_TEST_DISABLED_ON_WIN32(WorldWithModelsSpawnedAfterLoad)) { this->LoadWorld("test/worlds/save_world.sdf"); @@ -215,7 +217,7 @@ TEST_F(SdfGeneratorFixture, WorldWithModelsSpawnedAfterLoad) ///////////////////////////////////////////////// // Test segfaults on Mac at startup, possible collision with test above? TEST_F(SdfGeneratorFixture, - IGN_UTILS_TEST_DISABLED_ON_MAC(ModelSpawnedWithNewName)) + IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(ModelSpawnedWithNewName)) { this->LoadWorld("test/worlds/save_world.sdf"); diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index c4dbf14231..18f0ed6e1b 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -26,6 +26,7 @@ #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Pose.hh" #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" @@ -42,7 +43,8 @@ class SceneBroadcasterTest }; ///////////////////////////////////////////////// -TEST_P(SceneBroadcasterTest, PoseInfo) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PoseInfo)) { // Start server ignition::gazebo::ServerConfig serverConfig; @@ -92,7 +94,7 @@ TEST_P(SceneBroadcasterTest, PoseInfo) } ///////////////////////////////////////////////// -TEST_P(SceneBroadcasterTest, SceneInfo) +TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneInfo)) { // Start server ignition::gazebo::ServerConfig serverConfig; @@ -138,7 +140,7 @@ TEST_P(SceneBroadcasterTest, SceneInfo) } ///////////////////////////////////////////////// -TEST_P(SceneBroadcasterTest, SceneGraph) +TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneGraph)) { // Start server ignition::gazebo::ServerConfig serverConfig; @@ -178,7 +180,7 @@ TEST_P(SceneBroadcasterTest, SceneGraph) ///////////////////////////////////////////////// /// Test whether the scene topic is published only when new entities are added -TEST_P(SceneBroadcasterTest, SceneTopic) +TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopic)) { // Start server ignition::gazebo::ServerConfig serverConfig; @@ -222,7 +224,8 @@ TEST_P(SceneBroadcasterTest, SceneTopic) ///////////////////////////////////////////////// /// Test whether the scene topic is published only when new entities are added -TEST_P(SceneBroadcasterTest, SceneTopicSensors) +TEST_P(SceneBroadcasterTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SceneTopicSensors)) { // Start server ignition::gazebo::ServerConfig serverConfig; @@ -273,7 +276,7 @@ TEST_P(SceneBroadcasterTest, SceneTopicSensors) ///////////////////////////////////////////////// /// Test whether the scene topic is published only when new entities are added -TEST_P(SceneBroadcasterTest, DeletedTopic) +TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(DeletedTopic)) { // Start server ignition::gazebo::ServerConfig serverConfig; @@ -333,7 +336,7 @@ TEST_P(SceneBroadcasterTest, DeletedTopic) ///////////////////////////////////////////////// /// Test whether the scene is updated when a model is spawned. -TEST_P(SceneBroadcasterTest, SpawnedModel) +TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedModel)) { // Start server ignition::gazebo::ServerConfig serverConfig; @@ -403,7 +406,7 @@ TEST_P(SceneBroadcasterTest, SpawnedModel) } ///////////////////////////////////////////////// -TEST_P(SceneBroadcasterTest, State) +TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(State)) { // Start server ignition::gazebo::ServerConfig serverConfig; @@ -514,12 +517,12 @@ TEST_P(SceneBroadcasterTest, State) } ///////////////////////////////////////////////// -TEST_P(SceneBroadcasterTest, StateStatic) +TEST_P(SceneBroadcasterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StateStatic)) { // Start server ignition::gazebo::ServerConfig serverConfig; serverConfig.SetSdfFile(std::string(PROJECT_SOURCE_PATH) + - "/examples/worlds/empty.sdf"); + "/test/worlds/empty.sdf"); gazebo::Server server(serverConfig); EXPECT_FALSE(server.Running()); diff --git a/test/integration/sdf_frame_semantics.cc b/test/integration/sdf_frame_semantics.cc index 23d5f9af9e..cdb579e224 100644 --- a/test/integration/sdf_frame_semantics.cc +++ b/test/integration/sdf_frame_semantics.cc @@ -22,6 +22,8 @@ #include #include +#include + #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/EventManager.hh" #include "ignition/gazebo/Link.hh" @@ -135,7 +137,8 @@ class SdfFrameSemanticsTest : public InternalFixture<::testing::Test> public: std::unique_ptr creator; }; -TEST_F(SdfFrameSemanticsTest, LinkRelativeTo) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(SdfFrameSemanticsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LinkRelativeTo)) { const std::string modelSdf = R"sdf( @@ -496,7 +499,8 @@ TEST_F(SdfFrameSemanticsTest, NestedModelsRelativeTo) EXPECT_EQ(link2ExpectedPose, this->GetPose(link2)); } -TEST_F(SdfFrameSemanticsTest, IncludeNestedModelsRelativeToTPE) +TEST_F(SdfFrameSemanticsTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(IncludeNestedModelsRelativeToTPE)) { std::string path = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models"; ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", path.c_str()); @@ -558,7 +562,8 @@ TEST_F(SdfFrameSemanticsTest, IncludeNestedModelsRelativeToTPE) EXPECT_EQ(nestedModelsLink01ExpectedPose, this->GetPose(nestedModelsLink01)); } -TEST_F(SdfFrameSemanticsTest, IncludeNestedModelsRelativeToDartsim) +TEST_F(SdfFrameSemanticsTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(IncludeNestedModelsRelativeToDartsim)) { std::string path = std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models"; ignition::common::setenv("IGN_GAZEBO_RESOURCE_PATH", path.c_str()); diff --git a/test/integration/sdf_include.cc b/test/integration/sdf_include.cc index 7a19d30b5f..dd9e5caadb 100644 --- a/test/integration/sdf_include.cc +++ b/test/integration/sdf_include.cc @@ -19,6 +19,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) @@ -32,7 +33,8 @@ class SdfInclude : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(SdfInclude, DownloadFromFuel) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(SdfInclude, IGN_UTILS_TEST_DISABLED_ON_WIN32(DownloadFromFuel)) { std::string path = common::cwd() + "/test_cache"; diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index 661a92819e..6165ee9620 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -87,6 +87,17 @@ void testDefaultTopics() std::vector publishers; transport::Node node; + // Sensors are created in a separate thread, so we sleep here to give them + // time + int sleep{0}; + int maxSleep{30}; + for (; sleep < maxSleep && !node.TopicInfo(topics.front(), publishers); + ++sleep) + { + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + } + ASSERT_LT(sleep, maxSleep); + for (const std::string &topic : topics) { bool result = node.TopicInfo(topic, publishers); diff --git a/test/integration/thruster.cc b/test/integration/thruster.cc index 591bad2580..af1ec159b8 100644 --- a/test/integration/thruster.cc +++ b/test/integration/thruster.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/Link.hh" #include "ignition/gazebo/Model.hh" @@ -194,7 +195,8 @@ void ThrusterTest::TestWorld(const std::string &_world, } ///////////////////////////////////////////////// -TEST_F(ThrusterTest, PIDControl) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(ThrusterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PIDControl)) { auto world = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "thruster_pid.sdf"); @@ -205,7 +207,7 @@ TEST_F(ThrusterTest, PIDControl) } ///////////////////////////////////////////////// -TEST_F(ThrusterTest, VelocityControl) +TEST_F(ThrusterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(VelocityControl)) { auto world = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds", "thruster_vel_cmd.sdf"); diff --git a/test/integration/touch_plugin.cc b/test/integration/touch_plugin.cc index 90b4080c06..60813c9a8a 100644 --- a/test/integration/touch_plugin.cc +++ b/test/integration/touch_plugin.cc @@ -19,6 +19,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" @@ -47,7 +48,8 @@ class TouchPluginTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(TouchPluginTest, OneLink) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(OneLink)) { this->StartServer("/test/worlds/touch_plugin.sdf"); @@ -105,7 +107,7 @@ TEST_F(TouchPluginTest, OneLink) } ////////////////////////////////////////////////// -TEST_F(TouchPluginTest, MultiLink) +TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(MultiLink)) { this->StartServer("/test/worlds/touch_plugin.sdf"); @@ -137,7 +139,7 @@ TEST_F(TouchPluginTest, MultiLink) } ////////////////////////////////////////////////// -TEST_F(TouchPluginTest, StartDisabled) +TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StartDisabled)) { this->StartServer("/test/worlds/touch_plugin.sdf"); @@ -185,7 +187,7 @@ TEST_F(TouchPluginTest, StartDisabled) } ////////////////////////////////////////////////// -TEST_F(TouchPluginTest, RemovalOfParentModel) +TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RemovalOfParentModel)) { this->StartServer("/test/worlds/touch_plugin.sdf"); @@ -224,7 +226,7 @@ TEST_F(TouchPluginTest, RemovalOfParentModel) /// Tests whether the plugin works when it is spawned after other entities have /// already been created and vice versa /// This test uses depends on the user_commands system -TEST_F(TouchPluginTest, SpawnedEntities) +TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(SpawnedEntities)) { std::string whiteBox = R"EOF( @@ -296,7 +298,7 @@ TEST_F(TouchPluginTest, SpawnedEntities) auto testFunc = [&](const std::string &_box1, const std::string &_box2) { this->server.reset(); - this->StartServer("/examples/worlds/empty.sdf"); + this->StartServer("/test/worlds/empty.sdf"); whiteTouched = false; req.set_sdf(_box1); diff --git a/test/integration/tracked_vehicle_system.cc b/test/integration/tracked_vehicle_system.cc index ea53742d3b..d98434d463 100644 --- a/test/integration/tracked_vehicle_system.cc +++ b/test/integration/tracked_vehicle_system.cc @@ -29,6 +29,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/Model.hh" @@ -563,7 +564,8 @@ class TrackedVehicleTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(TrackedVehicleTest, PublishCmd) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(TrackedVehicleTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) { this->TestPublishCmd( std::string(PROJECT_SOURCE_PATH) + @@ -573,7 +575,7 @@ TEST_F(TrackedVehicleTest, PublishCmd) } ///////////////////////////////////////////////// -TEST_F(TrackedVehicleTest, Conveyor) +TEST_F(TrackedVehicleTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Conveyor)) { this->TestConveyor( std::string(PROJECT_SOURCE_PATH) + diff --git a/test/integration/triggered_publisher.cc b/test/integration/triggered_publisher.cc index e8917738f6..9590a7c421 100644 --- a/test/integration/triggered_publisher.cc +++ b/test/integration/triggered_publisher.cc @@ -27,6 +27,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -90,7 +91,9 @@ bool waitUntil(int _timeoutMs, Pred _pred) ///////////////////////////////////////////////// /// Check that empty message types do not need any data to be specified in the /// configuration -TEST_F(TriggeredPublisherTest, EmptyInputEmptyOutput) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(EmptyInputEmptyOutput)) { transport::Node node; auto inputPub = node.Advertise("/in_0"); @@ -114,7 +117,8 @@ TEST_F(TriggeredPublisherTest, EmptyInputEmptyOutput) } ///////////////////////////////////////////////// -TEST_F(TriggeredPublisherTest, WrongInputMessageTypeDoesNotMatch) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(WrongInputMessageTypeDoesNotMatch)) { transport::Node node; auto inputPub = node.Advertise("/in_0"); @@ -137,7 +141,8 @@ TEST_F(TriggeredPublisherTest, WrongInputMessageTypeDoesNotMatch) } ///////////////////////////////////////////////// -TEST_F(TriggeredPublisherTest, InputMessagesTriggerOutputs) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(InputMessagesTriggerOutputs)) { transport::Node node; auto inputPub = node.Advertise("/in_1"); @@ -162,7 +167,8 @@ TEST_F(TriggeredPublisherTest, InputMessagesTriggerOutputs) } ///////////////////////////////////////////////// -TEST_F(TriggeredPublisherTest, MultipleOutputsForOneInput) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MultipleOutputsForOneInput)) { transport::Node node; auto inputPub = node.Advertise("/in_2"); @@ -207,7 +213,8 @@ TEST_F(TriggeredPublisherTest, MultipleOutputsForOneInput) } ///////////////////////////////////////////////// -TEST_F(TriggeredPublisherTest, ExactMatchBooleanInputs) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(ExactMatchBooleanInputs)) { transport::Node node; auto inputPub = node.Advertise("/in_3"); @@ -240,7 +247,8 @@ TEST_F(TriggeredPublisherTest, ExactMatchBooleanInputs) } ///////////////////////////////////////////////// -TEST_F(TriggeredPublisherTest, MatchersWithLogicTypeAttribute) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MatchersWithLogicTypeAttribute)) { transport::Node node; auto inputPub = node.Advertise("/in_4"); @@ -276,7 +284,8 @@ TEST_F(TriggeredPublisherTest, MatchersWithLogicTypeAttribute) } ///////////////////////////////////////////////// -TEST_F(TriggeredPublisherTest, MultipleMatchersAreAnded) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(MultipleMatchersAreAnded)) { transport::Node node; auto inputPub = node.Advertise("/in_5"); @@ -301,7 +310,7 @@ TEST_F(TriggeredPublisherTest, MultipleMatchersAreAnded) } ///////////////////////////////////////////////// -TEST_F(TriggeredPublisherTest, FieldMatchers) +TEST_F(TriggeredPublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(FieldMatchers)) { transport::Node node; auto inputPub = node.Advertise("/in_6"); @@ -340,7 +349,9 @@ TEST_F(TriggeredPublisherTest, FieldMatchers) ///////////////////////////////////////////////// /// Tests that if the specified field is a repeated field, a partial match is /// used when comparing against the input. -TEST_F(TriggeredPublisherTest, FieldMatchersWithRepeatedFieldsUsePartialMatches) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32( + FieldMatchersWithRepeatedFieldsUsePartialMatches)) { transport::Node node; auto inputPub = node.Advertise("/in_7"); @@ -377,7 +388,8 @@ TEST_F(TriggeredPublisherTest, FieldMatchersWithRepeatedFieldsUsePartialMatches) EXPECT_EQ(1u, recvCount); } -TEST_F(TriggeredPublisherTest, WrongInputWhenRepeatedSubFieldExpected) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(WrongInputWhenRepeatedSubFieldExpected)) { transport::Node node; auto inputPub = node.Advertise("/in_7"); @@ -406,8 +418,8 @@ TEST_F(TriggeredPublisherTest, WrongInputWhenRepeatedSubFieldExpected) /// fields by specifying the containing field of the repeated field in the /// "field" attribute and setting the desired values of the repeated field in /// the value of the tag. -TEST_F(TriggeredPublisherTest, - FieldMatchersWithRepeatedFieldsInValueUseFullMatches) +TEST_F(TriggeredPublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32( + FieldMatchersWithRepeatedFieldsInValueUseFullMatches)) { transport::Node node; auto inputPub = node.Advertise("/in_8"); @@ -448,8 +460,8 @@ TEST_F(TriggeredPublisherTest, /// Tests that full matchers can be used with repeated fields by specifying the /// desired values of the repeated field in the value of the tag. The /// message created from the value of must be a full match of the input. -TEST_F(TriggeredPublisherTest, - FullMatchersWithRepeatedFieldsInValueUseFullMatches) +TEST_F(TriggeredPublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32( + FullMatchersWithRepeatedFieldsInValueUseFullMatches)) { transport::Node node; auto inputPub = node.Advertise("/in_9"); @@ -476,7 +488,8 @@ TEST_F(TriggeredPublisherTest, EXPECT_EQ(1u, recvCount); } -TEST_F(TriggeredPublisherTest, FullMatchersAcceptToleranceParam) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(FullMatchersAcceptToleranceParam)) { transport::Node node; auto inputPub = node.Advertise("/in_10"); @@ -503,7 +516,8 @@ TEST_F(TriggeredPublisherTest, FullMatchersAcceptToleranceParam) EXPECT_EQ(3u, recvCount); } -TEST_F(TriggeredPublisherTest, FieldMatchersAcceptToleranceParam) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(FieldMatchersAcceptToleranceParam)) { transport::Node node; auto inputPub = node.Advertise("/in_11"); @@ -532,7 +546,8 @@ TEST_F(TriggeredPublisherTest, FieldMatchersAcceptToleranceParam) EXPECT_EQ(3u, recvCount); } -TEST_F(TriggeredPublisherTest, SubfieldsOfRepeatedFieldsNotSupported) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(SubfieldsOfRepeatedFieldsNotSupported)) { transport::Node node; auto inputPub = node.Advertise("/in_12"); @@ -562,7 +577,7 @@ TEST_F(TriggeredPublisherTest, SubfieldsOfRepeatedFieldsNotSupported) EXPECT_EQ(0u, recvCount); } -TEST_F(TriggeredPublisherTest, TriggerDelay) +TEST_F(TriggeredPublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TriggerDelay)) { transport::Node node; auto inputPub = node.Advertise("/in_13"); @@ -597,7 +612,8 @@ TEST_F(TriggeredPublisherTest, TriggerDelay) EXPECT_EQ(pubCount, recvCount); } -TEST_F(TriggeredPublisherTest, WrongInputWhenRepeatedFieldExpected) +TEST_F(TriggeredPublisherTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(WrongInputWhenRepeatedFieldExpected)) { transport::Node node; auto inputPub = node.Advertise("/invalid_topic"); diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 20cdaa22f3..18f4d4a432 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -25,6 +25,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Light.hh" #include "ignition/gazebo/components/Link.hh" @@ -49,12 +50,13 @@ class UserCommandsTest : public InternalFixture<::testing::Test> }; ///////////////////////////////////////////////// -TEST_F(UserCommandsTest, Create) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Create)) { // Start server ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + - "/examples/worlds/empty.sdf"; + "/test/worlds/empty.sdf"; serverConfig.SetSdfFile(sdfFile); Server server(serverConfig); @@ -328,7 +330,7 @@ TEST_F(UserCommandsTest, Create) } ///////////////////////////////////////////////// -TEST_F(UserCommandsTest, Remove) +TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Remove)) { // Start server ServerConfig serverConfig; @@ -516,7 +518,7 @@ TEST_F(UserCommandsTest, Remove) } ///////////////////////////////////////////////// -TEST_F(UserCommandsTest, Pose) +TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Pose)) { // Start server ServerConfig serverConfig; @@ -689,7 +691,8 @@ TEST_F(UserCommandsTest, Pose) } ///////////////////////////////////////////////// -TEST_F(UserCommandsTest, Light) +// https://github.com/ignitionrobotics/ign-gazebo/issues/634 +TEST_F(UserCommandsTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Light)) { // Start server ServerConfig serverConfig; @@ -941,7 +944,7 @@ TEST_F(UserCommandsTest, Light) } ///////////////////////////////////////////////// -TEST_F(UserCommandsTest, Physics) +TEST_F(UserCommandsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(Physics)) { // Start server ServerConfig serverConfig; @@ -975,7 +978,7 @@ TEST_F(UserCommandsTest, Physics) auto physicsComp = ecm->Component(worldEntity); ASSERT_NE(nullptr, physicsComp); EXPECT_DOUBLE_EQ(0.001, physicsComp->Data().MaxStepSize()); - EXPECT_DOUBLE_EQ(1.0, physicsComp->Data().RealTimeFactor()); + EXPECT_DOUBLE_EQ(0.0, physicsComp->Data().RealTimeFactor()); // Set physics properties msgs::Physics req; diff --git a/test/integration/velocity_control_system.cc b/test/integration/velocity_control_system.cc index 392b2d6345..2ec01ae5a8 100644 --- a/test/integration/velocity_control_system.cc +++ b/test/integration/velocity_control_system.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include "ignition/gazebo/components/Link.hh" #include "ignition/gazebo/components/Name.hh" @@ -230,7 +231,8 @@ class VelocityControlTest }; ///////////////////////////////////////////////// -TEST_P(VelocityControlTest, PublishCmd) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_P(VelocityControlTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd)) { TestPublishCmd( std::string(PROJECT_SOURCE_PATH) + "/test/worlds/velocity_control.sdf", @@ -238,7 +240,7 @@ TEST_P(VelocityControlTest, PublishCmd) } ///////////////////////////////////////////////// -TEST_P(VelocityControlTest, PublishLinkCmd) +TEST_P(VelocityControlTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishLinkCmd)) { TestPublishLinkCmd( std::string(PROJECT_SOURCE_PATH) + "/test/worlds/velocity_control.sdf", diff --git a/test/integration/wheel_slip.cc b/test/integration/wheel_slip.cc index 6e931b02ea..24a9f3e697 100644 --- a/test/integration/wheel_slip.cc +++ b/test/integration/wheel_slip.cc @@ -23,6 +23,7 @@ #include #include #include +#include #include #include @@ -103,7 +104,8 @@ class WheelSlipTest : public InternalFixture<::testing::Test> }; }; -TEST_F(WheelSlipTest, TireDrum) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TireDrum)) { const double metersPerMile = 1609.34; const double secondsPerHour = 3600.0; @@ -369,7 +371,7 @@ TEST_F(WheelSlipTest, TireDrum) server.Run(true, 250, false); } -TEST_F(WheelSlipTest, TricyclesUphill) +TEST_F(WheelSlipTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TricyclesUphill)) { ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + diff --git a/test/integration/wind_effects.cc b/test/integration/wind_effects.cc index ea4dd728dc..ac30ffe240 100644 --- a/test/integration/wind_effects.cc +++ b/test/integration/wind_effects.cc @@ -20,6 +20,7 @@ #include #include #include +#include #include "ignition/gazebo/Link.hh" #include "ignition/gazebo/Server.hh" @@ -184,7 +185,8 @@ class BlockingPublisher ///////////////////////////////////////////////// /// Check if 'enable_wind' set only in works -TEST_F(WindEffectsTest, WindEnabledInModel) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST_F(WindEffectsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(WindEnabledInModel)) { this->StartServer("/test/worlds/wind_effects.sdf"); @@ -201,7 +203,7 @@ TEST_F(WindEffectsTest, WindEnabledInModel) ///////////////////////////////////////////////// /// Check if 'enable_wind' set only in works -TEST_F(WindEffectsTest, WindEnabledInLink) +TEST_F(WindEffectsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(WindEnabledInLink)) { this->StartServer("/test/worlds/wind_effects.sdf"); @@ -218,7 +220,7 @@ TEST_F(WindEffectsTest, WindEnabledInLink) //////////////////////////////////////////////// -TEST_F(WindEffectsTest , WindForce) +TEST_F(WindEffectsTest , IGN_UTILS_TEST_DISABLED_ON_WIN32(WindForce)) { this->StartServer("/test/worlds/wind_effects.sdf"); LinkComponentRecorder linkAccelerations( @@ -255,7 +257,7 @@ TEST_F(WindEffectsTest , WindForce) } //////////////////////////////////////////////// -TEST_F(WindEffectsTest , TopicsAndServices) +TEST_F(WindEffectsTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(TopicsAndServices)) { using namespace std::chrono_literals; @@ -322,7 +324,8 @@ TEST_F(WindEffectsTest , TopicsAndServices) /// Test if adding a link with wind after first iteration adds /// WorldLinearVelocity component properly -TEST_F(WindEffectsTest, WindEntityAddedAfterStart) +TEST_F(WindEffectsTest, + IGN_UTILS_TEST_DISABLED_ON_WIN32(WindEntityAddedAfterStart)) { const std::string windBox = R"EOF( diff --git a/test/performance/level_manager.cc b/test/performance/level_manager.cc index 172c70db95..ccd9032c31 100644 --- a/test/performance/level_manager.cc +++ b/test/performance/level_manager.cc @@ -22,6 +22,7 @@ #include #include #include +#include #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" @@ -30,7 +31,8 @@ using namespace ignition; using namespace gazebo; -TEST(LevelManagerPerfrormance, LevelVsNoLevel) +// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175 +TEST(LevelManagerPerfrormance, IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelVsNoLevel)) { using namespace std::chrono; diff --git a/test/worlds/ackermann_steering.sdf b/test/worlds/ackermann_steering.sdf index 28a3b3d432..fbc52aacbe 100644 --- a/test/worlds/ackermann_steering.sdf +++ b/test/worlds/ackermann_steering.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/altimeter.sdf b/test/worlds/altimeter.sdf index 7b8c209632..7e93238220 100644 --- a/test/worlds/altimeter.sdf +++ b/test/worlds/altimeter.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/battery.sdf b/test/worlds/battery.sdf index bc5f91d44d..9078867090 100644 --- a/test/worlds/battery.sdf +++ b/test/worlds/battery.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 + + 1 0 0 0 0 0 + false + + 0 0 0.5 0 0 0 + + + + 1 1 1 + + + + + + + linear_battery_topics + 12.592 + 12.694 + -3.1424 + 1.2009 + 1.2009 + 0.061523 + 1.9499 + + 500 + /battery/discharge1 + /battery/discharge2 + + + + diff --git a/test/worlds/breadcrumbs.sdf b/test/worlds/breadcrumbs.sdf index fae8d86898..a8b75f9899 100644 --- a/test/worlds/breadcrumbs.sdf +++ b/test/worlds/breadcrumbs.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 .001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/collada_world_exporter.sdf b/test/worlds/collada_world_exporter.sdf index b65709b628..01f7ea7da4 100644 --- a/test/worlds/collada_world_exporter.sdf +++ b/test/worlds/collada_world_exporter.sdf @@ -1,6 +1,10 @@ + + 0 + + + + 0 + + + 0 + + diff --git a/test/worlds/contact.sdf b/test/worlds/contact.sdf index 395e450dcc..10c4afb1da 100644 --- a/test/worlds/contact.sdf +++ b/test/worlds/contact.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/conveyor.sdf b/test/worlds/conveyor.sdf index f4cd000ad8..f33ba10c3f 100644 --- a/test/worlds/conveyor.sdf +++ b/test/worlds/conveyor.sdf @@ -6,7 +6,7 @@ --> 0.001 - 10.0 + 0 + + 0 + + diff --git a/test/worlds/depth_camera_sensor.sdf b/test/worlds/depth_camera_sensor.sdf index 06bd27f558..89e791e83d 100644 --- a/test/worlds/depth_camera_sensor.sdf +++ b/test/worlds/depth_camera_sensor.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/diff_drive.sdf b/test/worlds/diff_drive.sdf index dcb6a1fc2e..bfd7352a00 100644 --- a/test/worlds/diff_drive.sdf +++ b/test/worlds/diff_drive.sdf @@ -2,9 +2,9 @@ - + 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 diff --git a/test/worlds/empty.sdf b/test/worlds/empty.sdf new file mode 100644 index 0000000000..d700350605 --- /dev/null +++ b/test/worlds/empty.sdf @@ -0,0 +1,67 @@ + + + + + 0.001 + 0 + + + + + + + + + + + + true + 0 0 10 0 0 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + diff --git a/test/worlds/event_trigger.sdf b/test/worlds/event_trigger.sdf index 2ccc046837..a0f4aa5e40 100644 --- a/test/worlds/event_trigger.sdf +++ b/test/worlds/event_trigger.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/falling.sdf b/test/worlds/falling.sdf index 9e69c968e6..cc09166afb 100644 --- a/test/worlds/falling.sdf +++ b/test/worlds/falling.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/fixed_world_joint.sdf b/test/worlds/fixed_world_joint.sdf index 114675b885..71e278023a 100644 --- a/test/worlds/fixed_world_joint.sdf +++ b/test/worlds/fixed_world_joint.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 diff --git a/test/worlds/follow_actor.sdf b/test/worlds/follow_actor.sdf index a02a444fc6..c1ac2046fe 100644 --- a/test/worlds/follow_actor.sdf +++ b/test/worlds/follow_actor.sdf @@ -1,6 +1,9 @@ + + 0 + diff --git a/test/worlds/friction.sdf b/test/worlds/friction.sdf index f4ce49cf4d..42f4c6da26 100644 --- a/test/worlds/friction.sdf +++ b/test/worlds/friction.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/gpu_lidar_sensor.sdf b/test/worlds/gpu_lidar_sensor.sdf index 165efb6adb..28d414d43d 100644 --- a/test/worlds/gpu_lidar_sensor.sdf +++ b/test/worlds/gpu_lidar_sensor.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + true diff --git a/test/worlds/imu.sdf b/test/worlds/imu.sdf index 4bd476afa6..e2983ccb31 100644 --- a/test/worlds/imu.sdf +++ b/test/worlds/imu.sdf @@ -4,7 +4,7 @@ 0 0 -5 0.001 - 1.0 + 0 0 0 -5 0.001 - 1.0 + 0 + + 0 + + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/ground plane/1 diff --git a/test/worlds/include_connected_nested_models.sdf b/test/worlds/include_connected_nested_models.sdf index f579ad30f1..3e03aa35eb 100644 --- a/test/worlds/include_connected_nested_models.sdf +++ b/test/worlds/include_connected_nested_models.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/joint_controller_invalid.sdf b/test/worlds/joint_controller_invalid.sdf index 4621474f99..45a8494ca4 100644 --- a/test/worlds/joint_controller_invalid.sdf +++ b/test/worlds/joint_controller_invalid.sdf @@ -1,6 +1,9 @@ + + 0 + diff --git a/test/worlds/joint_position_controller.sdf b/test/worlds/joint_position_controller.sdf index d38f710aac..9a15596021 100644 --- a/test/worlds/joint_position_controller.sdf +++ b/test/worlds/joint_position_controller.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/joint_trajectory_controller.sdf b/test/worlds/joint_trajectory_controller.sdf index 69f9ca0d97..25e6e1547e 100644 --- a/test/worlds/joint_trajectory_controller.sdf +++ b/test/worlds/joint_trajectory_controller.sdf @@ -2,6 +2,9 @@ + + 0 + diff --git a/test/worlds/level_performance.sdf b/test/worlds/level_performance.sdf index febf0168e6..2ba3d61de0 100644 --- a/test/worlds/level_performance.sdf +++ b/test/worlds/level_performance.sdf @@ -7,6 +7,10 @@ --> + + 0 + + diff --git a/test/worlds/levels.sdf b/test/worlds/levels.sdf index f0724beedb..ce2568ec70 100644 --- a/test/worlds/levels.sdf +++ b/test/worlds/levels.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/levels_no_performers.sdf b/test/worlds/levels_no_performers.sdf index 2332f0d329..a83859439d 100644 --- a/test/worlds/levels_no_performers.sdf +++ b/test/worlds/levels_no_performers.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/lift_drag.sdf b/test/worlds/lift_drag.sdf index 4926c4d9a8..2ee782834c 100644 --- a/test/worlds/lift_drag.sdf +++ b/test/worlds/lift_drag.sdf @@ -2,6 +2,10 @@ + + 0 + + + + 0 + 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/log_record_dbl_pendulum.sdf b/test/worlds/log_record_dbl_pendulum.sdf index 6b79cc1a43..6aa86c0955 100644 --- a/test/worlds/log_record_dbl_pendulum.sdf +++ b/test/worlds/log_record_dbl_pendulum.sdf @@ -10,7 +10,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/logical_audio_sensor_plugin.sdf b/test/worlds/logical_audio_sensor_plugin.sdf index acd2318c7e..4bc8537dba 100644 --- a/test/worlds/logical_audio_sensor_plugin.sdf +++ b/test/worlds/logical_audio_sensor_plugin.sdf @@ -1,6 +1,10 @@ + + 0 + + 0 0 0 0 0 0 diff --git a/test/worlds/logical_audio_sensor_plugin_services.sdf b/test/worlds/logical_audio_sensor_plugin_services.sdf index 5722016b69..47b4ec6fc3 100644 --- a/test/worlds/logical_audio_sensor_plugin_services.sdf +++ b/test/worlds/logical_audio_sensor_plugin_services.sdf @@ -1,6 +1,10 @@ + + 0 + + 0 0 0 0 0 0 diff --git a/test/worlds/logical_camera_sensor.sdf b/test/worlds/logical_camera_sensor.sdf index 96623b7d8e..9ec9feeaed 100644 --- a/test/worlds/logical_camera_sensor.sdf +++ b/test/worlds/logical_camera_sensor.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 0.94 0.76 -0.12 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.005 - 1.0 + 0 diff --git a/test/worlds/nested_model.sdf b/test/worlds/nested_model.sdf index b22c0dd17d..06063d67eb 100644 --- a/test/worlds/nested_model.sdf +++ b/test/worlds/nested_model.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/odometry_publisher.sdf b/test/worlds/odometry_publisher.sdf index e572a8cc88..ccda8141bd 100644 --- a/test/worlds/odometry_publisher.sdf +++ b/test/worlds/odometry_publisher.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.01 - 1.0 + 0 diff --git a/test/worlds/only_canonical_link_moves.sdf b/test/worlds/only_canonical_link_moves.sdf index 4afef7d849..5649e3facc 100644 --- a/test/worlds/only_canonical_link_moves.sdf +++ b/test/worlds/only_canonical_link_moves.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/optical_tactile_plugin.sdf b/test/worlds/optical_tactile_plugin.sdf index 8c8a5770b5..253a94b3ed 100644 --- a/test/worlds/optical_tactile_plugin.sdf +++ b/test/worlds/optical_tactile_plugin.sdf @@ -2,6 +2,10 @@ + + 0 + + diff --git a/test/worlds/particle_emitter.sdf b/test/worlds/particle_emitter.sdf index 0d15a8c2dc..63aa39e236 100644 --- a/test/worlds/particle_emitter.sdf +++ b/test/worlds/particle_emitter.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 diff --git a/test/worlds/particle_emitter2.sdf b/test/worlds/particle_emitter2.sdf index 4b32c57574..ca643ae13e 100644 --- a/test/worlds/particle_emitter2.sdf +++ b/test/worlds/particle_emitter2.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/performers.sdf b/test/worlds/performers.sdf index de0f736973..ec194696e9 100644 --- a/test/worlds/performers.sdf +++ b/test/worlds/performers.sdf @@ -1,6 +1,10 @@ + + 0 + + true diff --git a/test/worlds/physics_options.sdf b/test/worlds/physics_options.sdf index d4fcae60e1..0351a2495e 100644 --- a/test/worlds/physics_options.sdf +++ b/test/worlds/physics_options.sdf @@ -8,6 +8,7 @@ pgs + 0 + + 0 + + diff --git a/test/worlds/plugins_empty.sdf b/test/worlds/plugins_empty.sdf index ac6128380c..6061dfccde 100644 --- a/test/worlds/plugins_empty.sdf +++ b/test/worlds/plugins_empty.sdf @@ -2,6 +2,10 @@ + + 0 + + diff --git a/test/worlds/pose_publisher.sdf b/test/worlds/pose_publisher.sdf index fadf485754..2bacec9d5d 100644 --- a/test/worlds/pose_publisher.sdf +++ b/test/worlds/pose_publisher.sdf @@ -4,7 +4,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/quadcopter_velocity_control.sdf b/test/worlds/quadcopter_velocity_control.sdf index fc8adea119..6a4d08b813 100644 --- a/test/worlds/quadcopter_velocity_control.sdf +++ b/test/worlds/quadcopter_velocity_control.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/resource_paths.sdf b/test/worlds/resource_paths.sdf index ff5c5910f4..84f44e79ab 100644 --- a/test/worlds/resource_paths.sdf +++ b/test/worlds/resource_paths.sdf @@ -1,6 +1,10 @@ + + 0 + + + + 0 + + diff --git a/test/worlds/revolute_joint_equilibrium.sdf b/test/worlds/revolute_joint_equilibrium.sdf index cf967f17b3..1af50f31cc 100644 --- a/test/worlds/revolute_joint_equilibrium.sdf +++ b/test/worlds/revolute_joint_equilibrium.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/rgbd_camera_sensor.sdf b/test/worlds/rgbd_camera_sensor.sdf index 6209bfe72b..abdfc56dda 100644 --- a/test/worlds/rgbd_camera_sensor.sdf +++ b/test/worlds/rgbd_camera_sensor.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 + + 0 + + diff --git a/test/worlds/sensor.sdf b/test/worlds/sensor.sdf index 1587a32736..fe6568e3f7 100644 --- a/test/worlds/sensor.sdf +++ b/test/worlds/sensor.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/shapes.sdf b/test/worlds/shapes.sdf index f5972cf0cb..eb1e3b196e 100644 --- a/test/worlds/shapes.sdf +++ b/test/worlds/shapes.sdf @@ -3,7 +3,7 @@ 0.001 - 1.0 + 0 diff --git a/test/worlds/static_diff_drive_vehicle.sdf b/test/worlds/static_diff_drive_vehicle.sdf index 179a11ef20..ddadbde39c 100644 --- a/test/worlds/static_diff_drive_vehicle.sdf +++ b/test/worlds/static_diff_drive_vehicle.sdf @@ -5,7 +5,7 @@ 0.001 - 1.0 + 0 0.001 - 1.0 + 0 0.001 - 1.0 + 0 1.0 + 0 - - 0 0 0.5 0 0 0 @@ -222,7 +221,7 @@ - + 0 0 -4.0 1.5707963267948966 0 0 diff --git a/test/worlds/touch_plugin.sdf b/test/worlds/touch_plugin.sdf index 4ff260b7f3..d108699e92 100644 --- a/test/worlds/touch_plugin.sdf +++ b/test/worlds/touch_plugin.sdf @@ -1,6 +1,10 @@ + + 0 + + diff --git a/test/worlds/tracked_vehicle_simple.sdf b/test/worlds/tracked_vehicle_simple.sdf index 5a54f56958..cbe39175b6 100644 --- a/test/worlds/tracked_vehicle_simple.sdf +++ b/test/worlds/tracked_vehicle_simple.sdf @@ -6,7 +6,7 @@ --> 0.001 - 1.0 + 0 1000 diff --git a/test/worlds/triball_drift.sdf b/test/worlds/triball_drift.sdf index 640216ac78..86c82ec066 100644 --- a/test/worlds/triball_drift.sdf +++ b/test/worlds/triball_drift.sdf @@ -2,6 +2,9 @@ + + 0 + 1 0 -9.8 + + 0 + + diff --git a/test/worlds/trisphere_cycle_wheel_slip.sdf b/test/worlds/trisphere_cycle_wheel_slip.sdf index 5edcbc4f68..bfab17d87c 100644 --- a/test/worlds/trisphere_cycle_wheel_slip.sdf +++ b/test/worlds/trisphere_cycle_wheel_slip.sdf @@ -2,6 +2,9 @@ + + 0 + -2 0 -9.8 0.001 - 1.0 + 0 0 0 0 + + 0 + +