Skip to content

Commit

Permalink
Merge pull request #1602 from gazebosim/scpeters/merge36
Browse files Browse the repository at this point in the history
Merge 3 ➡️ 6 part1
  • Loading branch information
scpeters authored Jul 20, 2022
2 parents 4f2a520 + 6310904 commit 8c66ef3
Show file tree
Hide file tree
Showing 10 changed files with 40 additions and 19 deletions.
5 changes: 3 additions & 2 deletions test/integration/altimeter_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,9 @@ void altimeterCb(const msgs::Altimeter &_msg)

/////////////////////////////////////////////////
// The test checks the world pose and sensor readings of a falling altimeter
// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175
TEST_F(AltimeterTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(ModelFalling))
// See: https://github.com/gazebosim/gz-sim/issues/1175
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(AltimeterTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(ModelFalling))
{
// Start server
ServerConfig serverConfig;
Expand Down
9 changes: 6 additions & 3 deletions test/integration/diff_drive_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -211,16 +211,19 @@ class DiffDriveTest : public InternalFixture<::testing::TestWithParam<int>>
};

/////////////////////////////////////////////////
// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175
TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd))
// See: https://github.com/gazebosim/gz-sim/issues/1175
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_P(DiffDriveTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PublishCmd))
{
TestPublishCmd(
std::string(PROJECT_SOURCE_PATH) + "/test/worlds/diff_drive.sdf",
"/model/vehicle/cmd_vel", "/model/vehicle/odometry");
}

/////////////////////////////////////////////////
TEST_P(DiffDriveTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmdCustomTopics))
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_P(DiffDriveTest,
IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PublishCmdCustomTopics))
{
TestPublishCmd(
std::string(PROJECT_SOURCE_PATH) +
Expand Down
8 changes: 5 additions & 3 deletions test/integration/level_manager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -179,8 +179,9 @@ class LevelManagerFixture : public InternalFixture<::testing::Test>

/////////////////////////////////////////////////
/// Check default level includes entities not included by other levels
// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175
TEST_F(LevelManagerFixture, IGN_UTILS_TEST_DISABLED_ON_WIN32(DefaultLevel))
// See: https://github.com/gazebosim/gz-sim/issues/1175
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(LevelManagerFixture, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(DefaultLevel))
{
std::vector<std::set<std::string>> levelEntityNamesList;

Expand Down Expand Up @@ -432,8 +433,9 @@ TEST_F(LevelManagerFixture,

///////////////////////////////////////////////
/// Check that buffers work properly with multiple performers
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(LevelManagerFixture,
IGN_UTILS_TEST_DISABLED_ON_WIN32(LevelBuffersWithMultiplePerformers))
IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(LevelBuffersWithMultiplePerformers))
{
ModelMover perf1(*this->server->EntityByName("sphere"));
ModelMover perf2(*this->server->EntityByName("box"));
Expand Down
4 changes: 3 additions & 1 deletion test/integration/logical_audio_sensor_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,9 @@ TEST_F(LogicalAudioTest,
"world/logical_audio_sensor/model/source_model/sensor/source_1");
}

TEST_F(LogicalAudioTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(LogicalAudioServices))
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(LogicalAudioTest,
IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(LogicalAudioServices))
{
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
Expand Down
8 changes: 6 additions & 2 deletions test/integration/multiple_servers.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <gtest/gtest.h>

#include <ignition/utils/ExtraTestMacros.hh>

#include "ignition/gazebo/Server.hh"
#include "ignition/gazebo/ServerConfig.hh"

Expand All @@ -32,7 +34,8 @@ class MultipleServers : public InternalFixture<::testing::TestWithParam<int>>
};

/////////////////////////////////////////////////
TEST_P(MultipleServers, TwoServersNonBlocking)
// See: https://github.com/gazebosim/gz-sim/issues/1544
TEST_P(MultipleServers, IGN_UTILS_TEST_DISABLED_ON_MAC(TwoServersNonBlocking))
{
ignition::gazebo::ServerConfig serverConfig;
serverConfig.SetSdfString(TestWorldSansPhysics::World());
Expand Down Expand Up @@ -72,7 +75,8 @@ TEST_P(MultipleServers, TwoServersNonBlocking)
}

/////////////////////////////////////////////////
TEST_P(MultipleServers, TwoServersMixedBlocking)
// See: https://github.com/gazebosim/gz-sim/issues/1544
TEST_P(MultipleServers, IGN_UTILS_TEST_DISABLED_ON_MAC(TwoServersMixedBlocking))
{
ignition::gazebo::ServerConfig serverConfig;
serverConfig.SetSdfString(TestWorldSansPhysics::World());
Expand Down
3 changes: 2 additions & 1 deletion test/integration/network_handshake.cc
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,8 @@ TEST_F(NetworkHandshake, IGN_UTILS_TEST_DISABLED_ON_WIN32(Handshake))
}

/////////////////////////////////////////////////
TEST_F(NetworkHandshake, IGN_UTILS_TEST_DISABLED_ON_WIN32(Updates))
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(NetworkHandshake, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(Updates))
{
auto pluginElem = std::make_shared<sdf::Element>();
pluginElem->SetName("plugin");
Expand Down
6 changes: 4 additions & 2 deletions test/integration/performer_detector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,10 @@ class PerformerDetectorTest : public InternalFixture<::testing::Test>

/////////////////////////////////////////////////
// Test that commanded motor speed is applied
// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175
TEST_F(PerformerDetectorTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(MovingPerformer))
// See: https://github.com/gazebosim/gz-sim/issues/1175
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(PerformerDetectorTest,
IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(MovingPerformer))
{
auto server = this->StartServer("/test/worlds/performer_detector.sdf");

Expand Down
7 changes: 5 additions & 2 deletions test/integration/pose_publisher_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -322,7 +322,9 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd))
}

/////////////////////////////////////////////////
TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(UpdateFrequency))
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(PosePublisherTest,
IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(UpdateFrequency))
{
// Start server
ServerConfig serverConfig;
Expand Down Expand Up @@ -643,8 +645,9 @@ TEST_F(PosePublisherTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StaticPosePublisher))
}

/////////////////////////////////////////////////
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(PosePublisherTest,
IGN_UTILS_TEST_DISABLED_ON_WIN32(StaticPoseUpdateFrequency))
IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(StaticPoseUpdateFrequency))
{
// Start server
ServerConfig serverConfig;
Expand Down
4 changes: 3 additions & 1 deletion test/integration/touch_plugin.cc
Original file line number Diff line number Diff line change
Expand Up @@ -187,7 +187,9 @@ TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(StartDisabled))
}

//////////////////////////////////////////////////
TEST_F(TouchPluginTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(RemovalOfParentModel))
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_F(TouchPluginTest,
IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(RemovalOfParentModel))
{
this->StartServer("/test/worlds/touch_plugin.sdf");

Expand Down
5 changes: 3 additions & 2 deletions test/integration/velocity_control_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -231,8 +231,9 @@ class VelocityControlTest
};

/////////////////////////////////////////////////
// See https://github.com/ignitionrobotics/ign-gazebo/issues/1175
TEST_P(VelocityControlTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(PublishCmd))
// See: https://github.com/gazebosim/gz-sim/issues/1175
// See: https://github.com/gazebosim/gz-sim/issues/630
TEST_P(VelocityControlTest, IGN_UTILS_TEST_ENABLED_ONLY_ON_LINUX(PublishCmd))
{
TestPublishCmd(
std::string(PROJECT_SOURCE_PATH) + "/test/worlds/velocity_control.sdf",
Expand Down

0 comments on commit 8c66ef3

Please sign in to comment.