Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use a custom Fuel cache location for tests #213

Merged
merged 4 commits into from
Jun 24, 2020
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
39 changes: 38 additions & 1 deletion src/SdfGenerator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -135,16 +135,43 @@ TEST(CompareElements, CompareWithDuplicateElements)
EXPECT_FALSE(isSubset(m1CompTest, m1));
}


const char *g_cacheLocation = nullptr;
chapulina marked this conversation as resolved.
Show resolved Hide resolved
class CustomCacheEnv : public ::testing::Environment
{
public: void SetUp() override
{
this->cacheLoc =
common::uniqueDirectoryPath(common::absPath("sdf_gen_test_cache"));
g_cacheLocation = this->cacheLoc.c_str();
common::createDirectory(g_cacheLocation);
ASSERT_TRUE(common::exists(g_cacheLocation));
}

public: void TearDown() override
{
common::removeAll(g_cacheLocation);
}

// g_cacheLocation will point to this string data.
private: std::string cacheLoc;
};

/////////////////////////////////////////////////
class ElementUpdateFixture : public ::testing::Test
{
public: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);

fuel_tools::ClientConfig config;
config.SetCacheLocation(g_cacheLocation);
this->fuelClient = std::make_unique<fuel_tools::FuelClient>(config);

auto fuelCb = [&](const std::string &_uri)
{
auto out = fuel_tools::fetchResource(_uri);
auto out =
fuel_tools::fetchResourceWithClient(_uri, *this->fuelClient.get());
if (!out.empty())
{
this->includeUriMap[out] = _uri;
Expand Down Expand Up @@ -195,6 +222,7 @@ class ElementUpdateFixture : public ::testing::Test
public: std::unique_ptr<SdfEntityCreator> creator;
public: msgs::SdfGeneratorConfig sdfGenConfig;
public: sdf_generator::IncludeUriMap includeUriMap;
public: std::unique_ptr<fuel_tools::FuelClient> fuelClient;
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -854,3 +882,12 @@ TEST_F(GenerateWorldFixture, ModelsInline)
EXPECT_TRUE(isSubset(this->root.Element(), newRoot.Element()));
}
}

/////////////////////////////////////////////////
/// Main
int main(int _argc, char **_argv)
{
::testing::InitGoogleTest(&_argc, _argv);
::testing::AddGlobalTestEnvironment(new CustomCacheEnv);
return RUN_ALL_TESTS();
}
174 changes: 74 additions & 100 deletions test/integration/breadcrumbs.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,27 @@
using namespace ignition;
using namespace gazebo;

const char *g_cacheLocation = nullptr;
class CustomCacheEnv : public ::testing::Environment
{
public: void SetUp() override
{
this->cacheLoc =
common::uniqueDirectoryPath(common::absPath("breadcrumbs_test_cache"));
g_cacheLocation = this->cacheLoc.c_str();
common::createDirectory(g_cacheLocation);
ASSERT_TRUE(common::exists(g_cacheLocation));
}

public: void TearDown() override
{
common::removeAll(g_cacheLocation);
}

// g_cacheLocation will point to this string data.
private: std::string cacheLoc;
};

class BreadcrumbsTest : public ::testing::Test
{
// Documentation inherited
Expand All @@ -47,24 +68,30 @@ class BreadcrumbsTest : public ::testing::Test
setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1);
}
public: void LoadWorld(const std::string &_path, bool _useLevels = false)
{
this->serverConfig.SetResourceCache(g_cacheLocation);
this->serverConfig.SetSdfFile(
common::joinPaths(PROJECT_SOURCE_PATH, _path));
this->serverConfig.SetUseLevels(_useLevels);

this->server = std::make_unique<Server>(this->serverConfig);
EXPECT_FALSE(this->server->Running());
EXPECT_FALSE(*this->server->Running(0));
using namespace std::chrono_literals;
this->server->SetUpdatePeriod(1ns);
}

public: ServerConfig serverConfig;
public: std::unique_ptr<Server> server;
};

/////////////////////////////////////////////////
// The test checks breadcrumbs are deployed at the correct pose
TEST_F(BreadcrumbsTest, DeployAtOffset)
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/breadcrumbs.sdf";
serverConfig.SetSdfFile(sdfFile);

Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);
this->LoadWorld("test/worlds/breadcrumbs.sdf");

test::Relay testSystem;
transport::Node node;
Expand Down Expand Up @@ -120,26 +147,16 @@ TEST_F(BreadcrumbsTest, DeployAtOffset)
}
});

server.AddSystem(testSystem.systemPtr);
server.Run(true, iterTestStart + 2001, false);
this->server->AddSystem(testSystem.systemPtr);
server->Run(true, iterTestStart + 2001, false);
azeey marked this conversation as resolved.
Show resolved Hide resolved
}

/////////////////////////////////////////////////
// The test checks max deployments
TEST_F(BreadcrumbsTest, MaxDeployments)
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/breadcrumbs.sdf";
serverConfig.SetSdfFile(sdfFile);

Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);
this->LoadWorld("test/worlds/breadcrumbs.sdf");

test::Relay testSystem;
transport::Node node;
Expand Down Expand Up @@ -184,8 +201,8 @@ TEST_F(BreadcrumbsTest, MaxDeployments)
}
});

server.AddSystem(testSystem.systemPtr);
server.Run(true, iterTestStart + 5001, false);
this->server->AddSystem(testSystem.systemPtr);
this->server->Run(true, iterTestStart + 5001, false);
}

/////////////////////////////////////////////////
Expand All @@ -194,17 +211,7 @@ TEST_F(BreadcrumbsTest, MaxDeployments)
TEST_F(BreadcrumbsTest, FuelDeploy)
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/breadcrumbs.sdf";
serverConfig.SetSdfFile(sdfFile);

Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);
this->LoadWorld("test/worlds/breadcrumbs.sdf");

test::Relay testSystem;
transport::Node node;
Expand Down Expand Up @@ -248,27 +255,16 @@ TEST_F(BreadcrumbsTest, FuelDeploy)
}
});

server.AddSystem(testSystem.systemPtr);
server.Run(true, nIters, false);
this->server->AddSystem(testSystem.systemPtr);
this->server->Run(true, nIters, false);
}

/////////////////////////////////////////////////
// The test checks that breadcrumbs can be performers
TEST_F(BreadcrumbsTest, Performer)
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/breadcrumbs.sdf";
serverConfig.SetSdfFile(sdfFile);
serverConfig.SetUseLevels(true);

Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);
this->LoadWorld("test/worlds/breadcrumbs.sdf");

test::Relay testSystem;
transport::Node node;
Expand Down Expand Up @@ -332,8 +328,8 @@ TEST_F(BreadcrumbsTest, Performer)
}
});

server.AddSystem(testSystem.systemPtr);
server.Run(true, nIters, false);
this->server->AddSystem(testSystem.systemPtr);
this->server->Run(true, nIters, false);
}

/////////////////////////////////////////////////
Expand All @@ -342,18 +338,7 @@ TEST_F(BreadcrumbsTest, Performer)
TEST_F(BreadcrumbsTest, PerformerSetVolume)
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/breadcrumbs.sdf";
serverConfig.SetSdfFile(sdfFile);
serverConfig.SetUseLevels(true);

Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);
this->LoadWorld("test/worlds/breadcrumbs.sdf", true);

test::Relay testSystem;
transport::Node node;
Expand Down Expand Up @@ -399,26 +384,16 @@ TEST_F(BreadcrumbsTest, PerformerSetVolume)
}
});

server.AddSystem(testSystem.systemPtr);
server.Run(true, nIters, false);
this->server->AddSystem(testSystem.systemPtr);
this->server->Run(true, nIters, false);
}

/////////////////////////////////////////////////
// The test verifies breadcrumbs physics is disabled using disable_physics_time
TEST_F(BreadcrumbsTest, DeployDisablePhysics)
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/breadcrumbs.sdf";
serverConfig.SetSdfFile(sdfFile);

Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);
this->LoadWorld("test/worlds/breadcrumbs.sdf");

test::Relay testSystem;
transport::Node node;
Expand Down Expand Up @@ -476,7 +451,7 @@ TEST_F(BreadcrumbsTest, DeployDisablePhysics)

// Verify that the breadcrumb stopped falling after 0.5s.
sdf::Root root;
root.Load(sdfFile);
root.Load(this->serverConfig.SdfFile());
const sdf::World *world = root.WorldByIndex(0);
double gz = world->Gravity().Z();
double z0 = 2.0;
Expand All @@ -486,8 +461,8 @@ TEST_F(BreadcrumbsTest, DeployDisablePhysics)
}
});

server.AddSystem(testSystem.systemPtr);
server.Run(true, iterTestStart + 2001, false);
this->server->AddSystem(testSystem.systemPtr);
this->server->Run(true, iterTestStart + 2001, false);
}

/////////////////////////////////////////////////
Expand All @@ -496,17 +471,7 @@ TEST_F(BreadcrumbsTest, DeployDisablePhysics)
TEST_F(BreadcrumbsTest, AllowRenaming)
{
// Start server
ServerConfig serverConfig;
const auto sdfFile = std::string(PROJECT_SOURCE_PATH) +
"/test/worlds/breadcrumbs.sdf";
serverConfig.SetSdfFile(sdfFile);

Server server(serverConfig);
EXPECT_FALSE(server.Running());
EXPECT_FALSE(*server.Running(0));

using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);
this->LoadWorld("test/worlds/breadcrumbs.sdf");

transport::Node node;
auto deployB1 =
Expand All @@ -516,21 +481,30 @@ TEST_F(BreadcrumbsTest, AllowRenaming)
auto renameDeploy =
node.Advertise<msgs::Empty>("/rename_deploy");

server.Run(true, 1, false);
this->server->Run(true, 1, false);
deployB1.Publish(msgs::Empty());
server.Run(true, 100, false);
EXPECT_TRUE(server.HasEntity("B1_0"));
this->server->Run(true, 100, false);
EXPECT_TRUE(this->server->HasEntity("B1_0"));

// Deploying via "/no_rename_deploy" will try to spawn B1_0, but since the
// model already exists, the spawn should fail.
auto curEntityCount = server.EntityCount().value();
auto curEntityCount = this->server->EntityCount().value();
noRenameDeploy.Publish(msgs::Empty());
server.Run(true, 100, false);
EXPECT_EQ(curEntityCount, server.EntityCount().value());
this->server->Run(true, 100, false);
EXPECT_EQ(curEntityCount, this->server->EntityCount().value());

// Deploying via "/rename_deploy" will try to spawn B1_0, but since the
// model already exists, it will spawn B1_0_1 instead.
renameDeploy.Publish(msgs::Empty());
server.Run(true, 100, false);
EXPECT_TRUE(server.HasEntity("B1_0_1"));
this->server->Run(true, 100, false);
EXPECT_TRUE(this->server->HasEntity("B1_0_1"));
}

/////////////////////////////////////////////////
/// Main
int main(int _argc, char **_argv)
{
::testing::InitGoogleTest(&_argc, _argv);
::testing::AddGlobalTestEnvironment(new CustomCacheEnv);
return RUN_ALL_TESTS();
}
Loading