Skip to content

Commit

Permalink
Don't use $HOME on most tests (InternalFixture) (#971)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <louise@openrobotics.org>
  • Loading branch information
chapulina authored Aug 13, 2021
1 parent 76c7b39 commit 4a5a33d
Show file tree
Hide file tree
Showing 67 changed files with 245 additions and 440 deletions.
9 changes: 3 additions & 6 deletions src/ComponentFactory_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,17 +21,14 @@
#include "ignition/gazebo/components/Factory.hh"
#include "ignition/gazebo/components/Pose.hh"

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

using namespace ignition;
using namespace gazebo;

/////////////////////////////////////////////////
class ComponentFactoryTest : public ::testing::Test
class ComponentFactoryTest : public InternalFixture<::testing::Test>
{
// Documentation inherited
protected: void SetUp() override
{
common::Console::SetVerbosity(4);
}
};

/////////////////////////////////////////////////
Expand Down
8 changes: 3 additions & 5 deletions src/Component_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,16 +29,14 @@
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/EntityComponentManager.hh"

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

using namespace ignition;
using namespace gazebo;

//////////////////////////////////////////////////
class ComponentTest : public ::testing::Test
class ComponentTest : public InternalFixture<::testing::Test>
{
protected: void SetUp() override
{
common::Console::SetVerbosity(4);
}
};

//////////////////////////////////////////////////
Expand Down
8 changes: 3 additions & 5 deletions src/EntityComponentManager_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/EntityComponentManager.hh"
#include "ignition/gazebo/config.hh"
#include "../test/helpers/EnvTestFixture.hh"

using namespace ignition;
using namespace gazebo;
Expand Down Expand Up @@ -93,12 +94,9 @@ class EntityCompMgrTest : public EntityComponentManager
}
};

class EntityComponentManagerFixture : public ::testing::TestWithParam<int>
class EntityComponentManagerFixture
: public InternalFixture<::testing::TestWithParam<int>>
{
public: void SetUp() override
{
common::Console::SetVerbosity(4);
}
public: EntityCompMgrTest manager;
};

Expand Down
8 changes: 3 additions & 5 deletions src/SdfEntityCreator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,8 @@
#include "ignition/gazebo/components/World.hh"
#include "ignition/gazebo/SdfEntityCreator.hh"

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

using namespace ignition;
using namespace gazebo;

Expand All @@ -63,12 +65,8 @@ class EntityCompMgrTest : public gazebo::EntityComponentManager
};

/////////////////////////////////////////////////
class SdfEntityCreatorTest : public ::testing::Test
class SdfEntityCreatorTest : public InternalFixture<::testing::Test>
{
public: void SetUp() override
{
ignition::common::Console::SetVerbosity(4);
}
public: EntityCompMgrTest ecm;
public: EventManager evm;
};
Expand Down
5 changes: 3 additions & 2 deletions src/SdfGenerator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include "ignition/gazebo/test_config.hh"

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

#include "SdfGenerator.hh"

Expand Down Expand Up @@ -147,11 +148,11 @@ TEST(CompareElements, CompareWithDuplicateElements)
}

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

fuel_tools::ClientConfig config;
config.SetCacheLocation(test::UniqueTestDirectoryEnv::Path());
Expand Down
18 changes: 14 additions & 4 deletions src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -870,17 +870,27 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback)
configFilename = "server.config";
}

std::string defaultConfig;
ignition::common::env(IGN_HOMEDIR, defaultConfig);
defaultConfig = ignition::common::joinPaths(defaultConfig, ".ignition",
"gazebo", configFilename);
std::string defaultConfigDir;
ignition::common::env(IGN_HOMEDIR, defaultConfigDir);
defaultConfigDir = ignition::common::joinPaths(defaultConfigDir, ".ignition",
"gazebo");

auto defaultConfig = ignition::common::joinPaths(defaultConfigDir,
configFilename);

if (!ignition::common::exists(defaultConfig))
{
auto installedConfig = ignition::common::joinPaths(
IGNITION_GAZEBO_SERVER_CONFIG_PATH,
configFilename);

if (!ignition::common::createDirectories(defaultConfigDir))
{
ignerr << "Failed to create directory [" << defaultConfigDir
<< "]." << std::endl;
return ret;
}

if (!ignition::common::exists(installedConfig))
{
ignerr << "Failed to copy installed config [" << installedConfig
Expand Down
4 changes: 0 additions & 4 deletions src/ServerPrivate.cc
Original file line number Diff line number Diff line change
Expand Up @@ -229,13 +229,11 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config)
bool hasRecordPath {false};
bool hasCompressPath {false};
bool hasRecordResources {false};
bool hasCompress {false};
bool hasRecordTopics {false};

std::string sdfRecordPath;
std::string sdfCompressPath;
bool sdfRecordResources;
bool sdfCompress;
std::vector<std::string> sdfRecordTopics;

if (sdfUseLogRecord)
Expand All @@ -246,8 +244,6 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config)
recordPluginElem->Get<std::string>("compress_path", "");
std::tie(sdfRecordResources, hasRecordResources) =
recordPluginElem->Get<bool>("record_resources", false);
std::tie(sdfCompress, hasCompress) =
recordPluginElem->Get<bool>("compress", false);

hasRecordTopics = recordPluginElem->HasElement("record_topic");
if (hasRecordTopics)
Expand Down
12 changes: 3 additions & 9 deletions src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,21 +39,15 @@

#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>
/////////////////////////////////////////////////
class ServerFixture : public InternalFixture<::testing::TestWithParam<int>>
{
protected: void SetUp() override
{
// Augment the system plugin path. In SetUp to avoid test order issues.
ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
(std::string(PROJECT_BINARY_PATH) + "/lib").c_str());

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

/////////////////////////////////////////////////
Expand Down
13 changes: 4 additions & 9 deletions src/SimulationRunner_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
#include "ignition/gazebo/Events.hh"
#include "ignition/gazebo/Util.hh"
#include "ignition/gazebo/config.hh"
#include "../test/helpers/EnvTestFixture.hh"
#include "SimulationRunner.hh"

using namespace ignition;
Expand All @@ -79,16 +80,10 @@ IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DoubleComponent",
}
}

class SimulationRunnerTest : public ::testing::TestWithParam<int>
/////////////////////////////////////////////////
class SimulationRunnerTest
: public InternalFixture<::testing::TestWithParam<int>>
{
// Documentation inherited
protected: void SetUp() override
{
common::Console::SetVerbosity(4);

common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
common::joinPaths(PROJECT_BINARY_PATH, "lib"));
}
};

std::vector<msgs::Clock> clockMsgs;
Expand Down
9 changes: 2 additions & 7 deletions src/TestFixture_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,20 +23,15 @@
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/ServerConfig.hh"
#include "ignition/gazebo/test_config.hh"
#include "../test/helpers/EnvTestFixture.hh"
#include "ignition/gazebo/TestFixture.hh"

using namespace ignition;
using namespace gazebo;

/////////////////////////////////////////////////
class TestFixtureTest : public ::testing::Test
class TestFixtureTest : public InternalFixture<::testing::Test>
{
// Documentation inherited
public: void SetUp() override
{
common::Console::SetVerbosity(4);
}

/// \brief Configure expectations
public: void Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
Expand Down
9 changes: 3 additions & 6 deletions src/Util_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,17 +34,14 @@
#include "ignition/gazebo/EntityComponentManager.hh"
#include "ignition/gazebo/Util.hh"

#include "helpers/EnvTestFixture.hh"

using namespace ignition;
using namespace gazebo;

/// \brief Tests for Util.hh
class UtilTest : public ::testing::Test
class UtilTest : public InternalFixture<::testing::Test>
{
// Documentation inherited
protected: void SetUp() override
{
common::Console::SetVerbosity(4);
}
};

/////////////////////////////////////////////////
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
#include "ignition/gazebo/gui/GuiRunner.hh"
#include "ignition/gazebo/EntityComponentManager.hh"
#include "ignition/gazebo/test_config.hh"
#include "../../../../test/helpers/EnvTestFixture.hh"

#include "JointPositionController.hh"

Expand All @@ -49,13 +50,8 @@ char **g_argv;
using namespace ignition;

/// \brief Tests for the joint position controller GUI plugin
class JointPositionControllerGui : public ::testing::Test
class JointPositionControllerGui : public InternalFixture<::testing::Test>
{
// Documentation inherited
protected: void SetUp() override
{
common::Console::SetVerbosity(4);
}
};

/////////////////////////////////////////////////
Expand Down
8 changes: 2 additions & 6 deletions src/gui/plugins/plot_3d/Plot3D_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include "ignition/gazebo/components/ParentEntity.hh"
#include "ignition/gazebo/EntityComponentManager.hh"
#include "ignition/gazebo/test_config.hh"
#include "../../../../test/helpers/EnvTestFixture.hh"

// Use this when forward-porting to v6
// #include "../../GuiRunner.hh"
Expand All @@ -55,13 +56,8 @@ char* g_argv[] =
using namespace ignition;

/// \brief Tests for the joint position controller GUI plugin
class Plot3D : public ::testing::Test
class Plot3D : public InternalFixture<::testing::Test>
{
// Documentation inherited
protected: void SetUp() override
{
common::Console::SetVerbosity(4);
}
};

/////////////////////////////////////////////////
Expand Down
5 changes: 4 additions & 1 deletion src/systems/physics/EntityFeatureMap_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <ignition/physics/config.hh>
#include <ignition/plugin/Loader.hh>

#include "../../../test/helpers/EnvTestFixture.hh"
#include "ignition/gazebo/EntityComponentManager.hh"

using namespace ignition;
Expand All @@ -46,10 +47,12 @@ using EnginePtrType =
physics::EnginePtr<physics::FeaturePolicy3d, MinimumFeatureList>;


class EntityFeatureMapFixture: public ::testing::Test
class EntityFeatureMapFixture: public InternalFixture<::testing::Test>
{
protected: void SetUp() override
{
InternalFixture::SetUp();

const std::string pluginLib = "libignition-physics-dartsim-plugin.so";

common::SystemPaths systemPaths;
Expand Down
61 changes: 61 additions & 0 deletions test/helpers/EnvTestFixture.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
/*
* Copyright (C) 2021 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/common/Filesystem.hh>
#include <ignition/common/Util.hh>
#include "ignition/gazebo/test_config.hh"

using namespace ignition;

/// \brief Common test setup for various tests
template <typename TestType>
class InternalFixture : public TestType
{
// Documentation inherited
protected: void SetUp() override
{
// Augment the system plugin path. In SetUp to avoid test order issues.
common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
common::joinPaths(std::string(PROJECT_BINARY_PATH), "lib").c_str());

common::Console::SetVerbosity(4);

// Change environment variable so that test files aren't written to $HOME
common::env(IGN_HOMEDIR, this->realHome);
EXPECT_TRUE(common::setenv(IGN_HOMEDIR, this->kFakeHome.c_str()));
}

// Documentation inherited
protected: void TearDown() override
{
// Restore $HOME
EXPECT_TRUE(common::setenv(IGN_HOMEDIR, this->realHome.c_str()));
}

/// \brief Directory to act as $HOME for tests
public: const std::string kFakeHome = common::joinPaths(PROJECT_BINARY_PATH,
"test", "fake_home");

/// \brief Store user's real $HOME to set it back at the end of tests.
public: std::string realHome;
};
#endif
Loading

0 comments on commit 4a5a33d

Please sign in to comment.