Skip to content

Commit

Permalink
👩‍🌾 Refactor UNIT_Server_TEST: move tests to integration (#594)
Browse files Browse the repository at this point in the history
Move several server interactions and fuel cached to their own
tests in integration.

Signed-off-by: Jose Luis Rivero <[email protected]>
  • Loading branch information
j-rivero authored Feb 2, 2021
1 parent 9bc088d commit 701b6ee
Show file tree
Hide file tree
Showing 5 changed files with 200 additions and 112 deletions.
113 changes: 1 addition & 112 deletions src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include <gtest/gtest.h>
#include <csignal>
#include <vector>
#include <ignition/common/Console.hh>
#include <ignition/common/StringUtils.hh>
#include <ignition/common/Util.hh>
#include <ignition/math/Rand.hh>
Expand All @@ -39,23 +38,12 @@

#include "plugins/MockSystem.hh"
#include "../test/helpers/Relay.hh"
#include "../test/helpers/EnvTestFixture.hh"

using namespace ignition;
using namespace ignition::gazebo;
using namespace std::chrono_literals;

class ServerFixture : public ::testing::TestWithParam<int>
{
protected: void SetUp() override
{
// Augment the system plugin path. In SetUp to avoid test order issues.
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);

ignition::common::Console::SetVerbosity(4);
}
};

/////////////////////////////////////////////////
TEST_P(ServerFixture, DefaultServerConfig)
{
Expand Down Expand Up @@ -624,79 +612,6 @@ TEST_P(ServerFixture, SigInt)
EXPECT_FALSE(*server.Running(0));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, TwoServersNonBlocking)
{
ignition::gazebo::ServerConfig serverConfig;
serverConfig.SetSdfString(TestWorldSansPhysics::World());

gazebo::Server server1(serverConfig);
gazebo::Server server2(serverConfig);
EXPECT_FALSE(server1.Running());
EXPECT_FALSE(*server1.Running(0));
EXPECT_FALSE(server2.Running());
EXPECT_FALSE(*server2.Running(0));
EXPECT_EQ(0u, *server1.IterationCount());
EXPECT_EQ(0u, *server2.IterationCount());

// Make the servers run fast.
server1.SetUpdatePeriod(1ns);
server2.SetUpdatePeriod(1ns);

// Start non-blocking
const size_t iters1 = 9999;
EXPECT_TRUE(server1.Run(false, iters1, false));

// Expect that we can't start another instance.
EXPECT_FALSE(server1.Run(true, 10, false));

// It's okay to start another server
EXPECT_TRUE(server2.Run(false, 500, false));

while (*server1.IterationCount() < iters1 || *server2.IterationCount() < 500)
IGN_SLEEP_MS(100);

EXPECT_EQ(iters1, *server1.IterationCount());
EXPECT_EQ(500u, *server2.IterationCount());
EXPECT_FALSE(server1.Running());
EXPECT_FALSE(*server1.Running(0));
EXPECT_FALSE(server2.Running());
EXPECT_FALSE(*server2.Running(0));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, TwoServersMixedBlocking)
{
ignition::gazebo::ServerConfig serverConfig;
serverConfig.SetSdfString(TestWorldSansPhysics::World());

gazebo::Server server1(serverConfig);
gazebo::Server server2(serverConfig);
EXPECT_FALSE(server1.Running());
EXPECT_FALSE(*server1.Running(0));
EXPECT_FALSE(server2.Running());
EXPECT_FALSE(*server2.Running(0));
EXPECT_EQ(0u, *server1.IterationCount());
EXPECT_EQ(0u, *server2.IterationCount());

// Make the servers run fast.
server1.SetUpdatePeriod(1ns);
server2.SetUpdatePeriod(1ns);

server1.Run(false, 10, false);
server2.Run(true, 1000, false);

while (*server1.IterationCount() < 10)
IGN_SLEEP_MS(100);

EXPECT_EQ(10u, *server1.IterationCount());
EXPECT_EQ(1000u, *server2.IterationCount());
EXPECT_FALSE(server1.Running());
EXPECT_FALSE(*server1.Running(0));
EXPECT_FALSE(server2.Running());
EXPECT_FALSE(*server2.Running(0));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, AddSystemWhileRunning)
{
Expand Down Expand Up @@ -902,32 +817,6 @@ TEST_P(ServerFixture, GetResourcePaths)
EXPECT_EQ("/home/user/another_path", res.data(1));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, CachedFuelWorld)
{
auto cachedWorldPath =
common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds");
setenv("IGN_FUEL_CACHE_PATH", cachedWorldPath.c_str(), 1);

ServerConfig serverConfig;
auto fuelWorldURL =
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world";
EXPECT_TRUE(serverConfig.SetSdfFile(fuelWorldURL));

EXPECT_EQ(fuelWorldURL, serverConfig.SdfFile());
EXPECT_TRUE(serverConfig.SdfString().empty());

// Check that world was loaded
auto server = Server(serverConfig);
EXPECT_NE(std::nullopt, server.Running(0));
EXPECT_FALSE(*server.Running(0));

server.Run(true /*blocking*/, 1, false/*paused*/);

EXPECT_NE(std::nullopt, server.Running(0));
EXPECT_FALSE(*server.Running(0));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, AddResourcePaths)
{
Expand Down
36 changes: 36 additions & 0 deletions test/helpers/EnvTestFixture.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
/*
* Copyright (C) 2020 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_GAZEBO_TEST_HELPERS_ENVTESTFIXTURE_HH_
#define IGNITION_GAZEBO_TEST_HELPERS_ENVTESTFIXTURE_HH_

#include <gtest/gtest.h>

#include <ignition/common/Console.hh>
#include "ignition/gazebo/test_config.hh"

class ServerFixture : public ::testing::TestWithParam<int>
{
protected: void SetUp() override
{
// Augment the system plugin path. In SetUp to avoid test order issues.
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);

ignition::common::Console::SetVerbosity(4);
}
};
#endif
2 changes: 2 additions & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ set(tests
events.cc
examples_build.cc
follow_actor_system.cc
fuel_cached_server.cc
imu_system.cc
joint_controller_system.cc
joint_position_controller_system.cc
Expand All @@ -31,6 +32,7 @@ set(tests
magnetometer_system.cc
model.cc
multicopter.cc
multiple_servers.cc
network_handshake.cc
performer_detector.cc
physics_system.cc
Expand Down
57 changes: 57 additions & 0 deletions test/integration/fuel_cached_server.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
/*
* Copyright (C) 2018 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <gtest/gtest.h>

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

#include "../test/helpers/EnvTestFixture.hh"

using namespace ignition;
using namespace ignition::gazebo;
using namespace std::chrono_literals;

/////////////////////////////////////////////////
TEST_P(ServerFixture, CachedFuelWorld)
{
auto cachedWorldPath =
common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds");
setenv("IGN_FUEL_CACHE_PATH", cachedWorldPath.c_str(), 1);

ServerConfig serverConfig;
auto fuelWorldURL =
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world";
EXPECT_TRUE(serverConfig.SetSdfFile(fuelWorldURL));

EXPECT_EQ(fuelWorldURL, serverConfig.SdfFile());
EXPECT_TRUE(serverConfig.SdfString().empty());

// Check that world was loaded
auto server = Server(serverConfig);
EXPECT_NE(std::nullopt, server.Running(0));
EXPECT_FALSE(*server.Running(0));

server.Run(true /*blocking*/, 1, false/*paused*/);

EXPECT_NE(std::nullopt, server.Running(0));
EXPECT_FALSE(*server.Running(0));
}

// Run multiple times. We want to make sure that static globals don't cause
// problems.
INSTANTIATE_TEST_SUITE_P(ServerRepeat, ServerFixture, ::testing::Range(1, 2));
104 changes: 104 additions & 0 deletions test/integration/multiple_servers.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
/*
* Copyright (C) 2018 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include <gtest/gtest.h>

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

#include "../test/helpers/EnvTestFixture.hh"

using namespace ignition;
using namespace ignition::gazebo;
using namespace std::chrono_literals;

/////////////////////////////////////////////////
TEST_P(ServerFixture, TwoServersNonBlocking)
{
ignition::gazebo::ServerConfig serverConfig;
serverConfig.SetSdfString(TestWorldSansPhysics::World());

gazebo::Server server1(serverConfig);
gazebo::Server server2(serverConfig);
EXPECT_FALSE(server1.Running());
EXPECT_FALSE(*server1.Running(0));
EXPECT_FALSE(server2.Running());
EXPECT_FALSE(*server2.Running(0));
EXPECT_EQ(0u, *server1.IterationCount());
EXPECT_EQ(0u, *server2.IterationCount());

// Make the servers run fast.
server1.SetUpdatePeriod(1ns);
server2.SetUpdatePeriod(1ns);

// Start non-blocking
const size_t iters1 = 9999;
EXPECT_TRUE(server1.Run(false, iters1, false));

// Expect that we can't start another instance.
EXPECT_FALSE(server1.Run(true, 10, false));

// It's okay to start another server
EXPECT_TRUE(server2.Run(false, 500, false));

while (*server1.IterationCount() < iters1 || *server2.IterationCount() < 500)
IGN_SLEEP_MS(100);

EXPECT_EQ(iters1, *server1.IterationCount());
EXPECT_EQ(500u, *server2.IterationCount());
EXPECT_FALSE(server1.Running());
EXPECT_FALSE(*server1.Running(0));
EXPECT_FALSE(server2.Running());
EXPECT_FALSE(*server2.Running(0));
}

/////////////////////////////////////////////////
TEST_P(ServerFixture, TwoServersMixedBlocking)
{
ignition::gazebo::ServerConfig serverConfig;
serverConfig.SetSdfString(TestWorldSansPhysics::World());

gazebo::Server server1(serverConfig);
gazebo::Server server2(serverConfig);
EXPECT_FALSE(server1.Running());
EXPECT_FALSE(*server1.Running(0));
EXPECT_FALSE(server2.Running());
EXPECT_FALSE(*server2.Running(0));
EXPECT_EQ(0u, *server1.IterationCount());
EXPECT_EQ(0u, *server2.IterationCount());

// Make the servers run fast.
server1.SetUpdatePeriod(1ns);
server2.SetUpdatePeriod(1ns);

server1.Run(false, 10, false);
server2.Run(true, 1000, false);

while (*server1.IterationCount() < 10)
IGN_SLEEP_MS(100);

EXPECT_EQ(10u, *server1.IterationCount());
EXPECT_EQ(1000u, *server2.IterationCount());
EXPECT_FALSE(server1.Running());
EXPECT_FALSE(*server1.Running(0));
EXPECT_FALSE(server2.Running());
EXPECT_FALSE(*server2.Running(0));
}

// Run multiple times. We want to make sure that static globals don't cause
// problems.
INSTANTIATE_TEST_SUITE_P(ServerRepeat, ServerFixture, ::testing::Range(1, 2));

0 comments on commit 701b6ee

Please sign in to comment.