From 4a5a33dca43aa12ad84453082125f9d6ab1bf47b Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 13 Aug 2021 14:53:46 -0700 Subject: [PATCH] Don't use $HOME on most tests (InternalFixture) (#971) Signed-off-by: Louise Poubel --- src/ComponentFactory_TEST.cc | 9 +-- src/Component_TEST.cc | 8 +-- src/EntityComponentManager_TEST.cc | 8 +-- src/SdfEntityCreator_TEST.cc | 8 +-- src/SdfGenerator_TEST.cc | 5 +- src/ServerConfig.cc | 18 ++++-- src/ServerPrivate.cc | 4 -- src/Server_TEST.cc | 12 +--- src/SimulationRunner_TEST.cc | 13 ++-- src/TestFixture_TEST.cc | 9 +-- src/Util_TEST.cc | 9 +-- .../JointPositionController_TEST.cc | 8 +-- src/gui/plugins/plot_3d/Plot3D_TEST.cc | 8 +-- src/systems/physics/EntityFeatureMap_TEST.cc | 5 +- test/helpers/EnvTestFixture.hh | 61 +++++++++++++++++++ test/integration/air_pressure_system.cc | 10 +-- test/integration/altimeter_system.cc | 10 +-- test/integration/apply_joint_force_system.cc | 10 +-- test/integration/battery_plugin.cc | 7 +-- test/integration/breadcrumbs.cc | 10 +-- test/integration/buoyancy.cc | 10 +-- .../integration/camera_video_record_system.cc | 10 +-- test/integration/collada_world_exporter.cc | 8 +-- test/integration/components.cc | 8 +-- test/integration/contact_system.cc | 10 +-- test/integration/depth_camera.cc | 10 +-- test/integration/detachable_joint.cc | 11 +--- test/integration/diff_drive_system.cc | 11 +--- test/integration/each_new_removed.cc | 9 +-- test/integration/entity_erase.cc | 9 +-- test/integration/events.cc | 12 ++-- test/integration/examples_build.cc | 4 +- test/integration/gpu_lidar.cc | 10 +-- test/integration/imu_system.cc | 10 +-- test/integration/joint_controller_system.cc | 10 +-- .../joint_position_controller_system.cc | 11 +--- .../joint_state_publisher_system.cc | 11 +--- .../kinetic_energy_monitor_system.cc | 10 +-- test/integration/level_manager.cc | 8 +-- .../level_manager_runtime_performers.cc | 8 +-- test/integration/lift_drag_system.cc | 10 +-- test/integration/link.cc | 8 +-- test/integration/log_system.cc | 11 +--- .../logical_audio_sensor_plugin.cc | 10 +-- test/integration/logical_camera_system.cc | 10 +-- test/integration/magnetometer_system.cc | 10 +-- test/integration/model.cc | 8 +-- test/integration/multicopter.cc | 11 +--- test/integration/network_handshake.cc | 9 +-- test/integration/performer_detector.cc | 11 +--- test/integration/physics_system.cc | 10 +-- test/integration/play_pause.cc | 8 ++- test/integration/pose_publisher_system.cc | 10 +-- test/integration/rgbd_camera.cc | 10 +-- test/integration/save_world.cc | 8 +-- test/integration/scene_broadcaster_system.cc | 12 ++-- test/integration/sdf_frame_semantics.cc | 10 +-- test/integration/sdf_include.cc | 8 ++- test/integration/sensors_system.cc | 8 +-- test/integration/thermal_system.cc | 10 +-- test/integration/touch_plugin.cc | 12 +--- test/integration/triggered_publisher.cc | 8 +-- test/integration/user_commands.cc | 10 +-- test/integration/velocity_control_system.cc | 12 +--- test/integration/wheel_slip.cc | 10 +-- test/integration/wind_effects.cc | 11 +--- test/integration/world.cc | 8 +-- 67 files changed, 245 insertions(+), 440 deletions(-) create mode 100644 test/helpers/EnvTestFixture.hh diff --git a/src/ComponentFactory_TEST.cc b/src/ComponentFactory_TEST.cc index 1f76270436..68957a503f 100644 --- a/src/ComponentFactory_TEST.cc +++ b/src/ComponentFactory_TEST.cc @@ -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); - } }; ///////////////////////////////////////////////// diff --git a/src/Component_TEST.cc b/src/Component_TEST.cc index 98899d3e8a..ea3bdd40a4 100644 --- a/src/Component_TEST.cc +++ b/src/Component_TEST.cc @@ -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); - } }; ////////////////////////////////////////////////// diff --git a/src/EntityComponentManager_TEST.cc b/src/EntityComponentManager_TEST.cc index 22c61b4e7c..824d30758b 100644 --- a/src/EntityComponentManager_TEST.cc +++ b/src/EntityComponentManager_TEST.cc @@ -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; @@ -93,12 +94,9 @@ class EntityCompMgrTest : public EntityComponentManager } }; -class EntityComponentManagerFixture : public ::testing::TestWithParam +class EntityComponentManagerFixture + : public InternalFixture<::testing::TestWithParam> { - public: void SetUp() override - { - common::Console::SetVerbosity(4); - } public: EntityCompMgrTest manager; }; diff --git a/src/SdfEntityCreator_TEST.cc b/src/SdfEntityCreator_TEST.cc index 4794c44a55..f6f3053d26 100644 --- a/src/SdfEntityCreator_TEST.cc +++ b/src/SdfEntityCreator_TEST.cc @@ -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; @@ -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; }; diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 7e834a6158..c4bbe58a31 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -40,6 +40,7 @@ #include "ignition/gazebo/test_config.hh" #include "helpers/UniqueTestDirectoryEnv.hh" +#include "helpers/EnvTestFixture.hh" #include "SdfGenerator.hh" @@ -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()); diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index fc3bb6d122..e6e7ee2b4f 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -870,10 +870,13 @@ 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)) { @@ -881,6 +884,13 @@ ignition::gazebo::loadPluginInfo(bool _isPlayback) 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 diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 22dc0848dd..580c0d11c7 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -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 sdfRecordTopics; if (sdfUseLogRecord) @@ -246,8 +244,6 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config) recordPluginElem->Get("compress_path", ""); std::tie(sdfRecordResources, hasRecordResources) = recordPluginElem->Get("record_resources", false); - std::tie(sdfCompress, hasCompress) = - recordPluginElem->Get("compress", false); hasRecordTopics = recordPluginElem->HasElement("record_topic"); if (hasRecordTopics) diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index 89e8c90387..8cce7b011d 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -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 +///////////////////////////////////////////////// +class ServerFixture : public InternalFixture<::testing::TestWithParam> { - 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); - } }; ///////////////////////////////////////////////// diff --git a/src/SimulationRunner_TEST.cc b/src/SimulationRunner_TEST.cc index 0048f1e15b..49000a8471 100644 --- a/src/SimulationRunner_TEST.cc +++ b/src/SimulationRunner_TEST.cc @@ -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; @@ -79,16 +80,10 @@ IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.DoubleComponent", } } -class SimulationRunnerTest : public ::testing::TestWithParam +///////////////////////////////////////////////// +class SimulationRunnerTest + : public InternalFixture<::testing::TestWithParam> { - // 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 clockMsgs; diff --git a/src/TestFixture_TEST.cc b/src/TestFixture_TEST.cc index 244e5b1846..4c6d244f87 100644 --- a/src/TestFixture_TEST.cc +++ b/src/TestFixture_TEST.cc @@ -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 &_sdf, diff --git a/src/Util_TEST.cc b/src/Util_TEST.cc index 7b117cdeda..c683faaec8 100644 --- a/src/Util_TEST.cc +++ b/src/Util_TEST.cc @@ -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); - } }; ///////////////////////////////////////////////// diff --git a/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc index 703fa7de84..72aa9b14cf 100644 --- a/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc +++ b/src/gui/plugins/joint_position_controller/JointPositionController_TEST.cc @@ -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" @@ -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); - } }; ///////////////////////////////////////////////// diff --git a/src/gui/plugins/plot_3d/Plot3D_TEST.cc b/src/gui/plugins/plot_3d/Plot3D_TEST.cc index f34e600409..6e085c3b34 100644 --- a/src/gui/plugins/plot_3d/Plot3D_TEST.cc +++ b/src/gui/plugins/plot_3d/Plot3D_TEST.cc @@ -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" @@ -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); - } }; ///////////////////////////////////////////////// diff --git a/src/systems/physics/EntityFeatureMap_TEST.cc b/src/systems/physics/EntityFeatureMap_TEST.cc index 9b842031b5..79c5314a87 100644 --- a/src/systems/physics/EntityFeatureMap_TEST.cc +++ b/src/systems/physics/EntityFeatureMap_TEST.cc @@ -30,6 +30,7 @@ #include #include +#include "../../../test/helpers/EnvTestFixture.hh" #include "ignition/gazebo/EntityComponentManager.hh" using namespace ignition; @@ -46,10 +47,12 @@ using EnginePtrType = physics::EnginePtr; -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; diff --git a/test/helpers/EnvTestFixture.hh b/test/helpers/EnvTestFixture.hh new file mode 100644 index 0000000000..e73636f6ac --- /dev/null +++ b/test/helpers/EnvTestFixture.hh @@ -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 + +#include +#include +#include +#include "ignition/gazebo/test_config.hh" + +using namespace ignition; + +/// \brief Common test setup for various tests +template +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 diff --git a/test/integration/air_pressure_system.cc b/test/integration/air_pressure_system.cc index be8e2d95f3..51e9000d90 100644 --- a/test/integration/air_pressure_system.cc +++ b/test/integration/air_pressure_system.cc @@ -30,20 +30,14 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test AirPressureTest system -class AirPressureTest : public ::testing::Test +class AirPressureTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/altimeter_system.cc b/test/integration/altimeter_system.cc index 5958888127..4b391963ac 100644 --- a/test/integration/altimeter_system.cc +++ b/test/integration/altimeter_system.cc @@ -36,20 +36,14 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test AltimeterTest system -class AltimeterTest : public ::testing::Test +class AltimeterTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; std::mutex mutex; diff --git a/test/integration/apply_joint_force_system.cc b/test/integration/apply_joint_force_system.cc index cc309c3119..c8423e88ae 100644 --- a/test/integration/apply_joint_force_system.cc +++ b/test/integration/apply_joint_force_system.cc @@ -32,6 +32,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 @@ -39,15 +40,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test fixture for ApplyJointForce system -class ApplyJointForceTestFixture : public ::testing::Test +class ApplyJointForceTestFixture : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/battery_plugin.cc b/test/integration/battery_plugin.cc index bd894299df..53f09d2153 100644 --- a/test/integration/battery_plugin.cc +++ b/test/integration/battery_plugin.cc @@ -39,18 +39,17 @@ #include "ignition/gazebo/components/Name.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; -class BatteryPluginTest : public ::testing::Test +class BatteryPluginTest : public InternalFixture<::testing::Test> { // Documentation inherited protected: void SetUp() override { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); + InternalFixture::SetUp(); auto plugin = sm.LoadPlugin("libMockSystem.so", "ignition::gazebo::MockSystem", diff --git a/test/integration/breadcrumbs.cc b/test/integration/breadcrumbs.cc index b458130b92..ed79d6eef6 100644 --- a/test/integration/breadcrumbs.cc +++ b/test/integration/breadcrumbs.cc @@ -40,19 +40,13 @@ #include "helpers/Relay.hh" #include "helpers/UniqueTestDirectoryEnv.hh" +#include "helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; -class BreadcrumbsTest : public ::testing::Test +class BreadcrumbsTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } public: void LoadWorld(const std::string &_path, bool _useLevels = false) { this->serverConfig.SetResourceCache(test::UniqueTestDirectoryEnv::Path()); diff --git a/test/integration/buoyancy.cc b/test/integration/buoyancy.cc index 41c7d530ec..77445fdd61 100644 --- a/test/integration/buoyancy.cc +++ b/test/integration/buoyancy.cc @@ -32,19 +32,13 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; -class BuoyancyTest : public ::testing::Test +class BuoyancyTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/camera_video_record_system.cc b/test/integration/camera_video_record_system.cc index 07968ccfea..e21b71fc98 100644 --- a/test/integration/camera_video_record_system.cc +++ b/test/integration/camera_video_record_system.cc @@ -26,20 +26,14 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test CameraVideoRecorder system -class CameraVideoRecorderTest : public ::testing::Test +class CameraVideoRecorderTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/collada_world_exporter.cc b/test/integration/collada_world_exporter.cc index ae677413c0..891c448870 100644 --- a/test/integration/collada_world_exporter.cc +++ b/test/integration/collada_world_exporter.cc @@ -24,18 +24,14 @@ #include "ignition/gazebo/test_config.hh" #include "helpers/UniqueTestDirectoryEnv.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; ///////////////////////////////////////////////// -class ColladaWorldExporterFixture : public ::testing::Test +class ColladaWorldExporterFixture : public InternalFixture<::testing::Test> { - public: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - } - public: void LoadWorld(const std::string &_path) { ServerConfig serverConfig; diff --git a/test/integration/components.cc b/test/integration/components.cc index 20ae6a89e2..3991468b6b 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -72,17 +72,13 @@ #include "ignition/gazebo/components/Visual.hh" #include "ignition/gazebo/components/World.hh" #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) - +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; -class ComponentsTest : public ::testing::Test +class ComponentsTest : public InternalFixture<::testing::Test> { - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/contact_system.cc b/test/integration/contact_system.cc index 589c3ff3c0..0a9014673b 100644 --- a/test/integration/contact_system.cc +++ b/test/integration/contact_system.cc @@ -30,19 +30,13 @@ #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; -class ContactSystemTest : public ::testing::Test +class ContactSystemTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index 9ecbe5aacd..c5d50777eb 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -29,6 +29,7 @@ #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" #define DEPTH_TOL 1e-4 @@ -36,15 +37,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test DepthCameraTest system -class DepthCameraTest : public ::testing::Test +class DepthCameraTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; std::mutex mutex; diff --git a/test/integration/detachable_joint.cc b/test/integration/detachable_joint.cc index 53ed104f31..bbbe91c66f 100644 --- a/test/integration/detachable_joint.cc +++ b/test/integration/detachable_joint.cc @@ -35,21 +35,14 @@ #include "ignition/gazebo/components/WindMode.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test DetachableJoint system -class DetachableJointTest : public ::testing::Test +class DetachableJointTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - public: void StartServer(const std::string &_sdfFile) { ServerConfig serverConfig; diff --git a/test/integration/diff_drive_system.cc b/test/integration/diff_drive_system.cc index d1b444ff10..e3a0081fa5 100644 --- a/test/integration/diff_drive_system.cc +++ b/test/integration/diff_drive_system.cc @@ -29,6 +29,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define tol 10e-4 @@ -37,16 +38,8 @@ using namespace gazebo; using namespace std::chrono_literals; /// \brief Test DiffDrive system -class DiffDriveTest : public ::testing::TestWithParam +class DiffDriveTest : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - /// \param[in] _sdfFile SDF file to load. /// \param[in] _cmdVelTopic Command velocity topic. /// \param[in] _odomTopic Odometry topic. diff --git a/test/integration/each_new_removed.cc b/test/integration/each_new_removed.cc index a7a88639bb..780e210250 100644 --- a/test/integration/each_new_removed.cc +++ b/test/integration/each_new_removed.cc @@ -30,6 +30,7 @@ #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace std::chrono_literals; @@ -38,14 +39,8 @@ using IntComponent = gazebo::components::Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.IntComponent", IntComponent) -class EachNewRemovedFixture : public ::testing::Test +class EachNewRemovedFixture : public InternalFixture<::testing::Test> { - 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()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/entity_erase.cc b/test/integration/entity_erase.cc index bb017612a4..f75da52514 100644 --- a/test/integration/entity_erase.cc +++ b/test/integration/entity_erase.cc @@ -19,19 +19,14 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; -class PhysicsSystemFixture : public ::testing::Test +class PhysicsSystemFixture : public InternalFixture<::testing::Test> { - 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()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/events.cc b/test/integration/events.cc index 34e95990df..b71fb4de52 100644 --- a/test/integration/events.cc +++ b/test/integration/events.cc @@ -24,18 +24,18 @@ #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) #include "plugins/EventTriggerSystem.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; -///////////////////////////////////////////////// -TEST(EventTrigger, TriggerPause) +class EventTrigger : public InternalFixture<::testing::Test> { - common::Console::SetVerbosity(4); - - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); +}; +///////////////////////////////////////////////// +TEST_F(EventTrigger, TriggerPause) +{ // Create server ServerConfig config; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + diff --git a/test/integration/examples_build.cc b/test/integration/examples_build.cc index d6c43d9750..bf40f70614 100644 --- a/test/integration/examples_build.cc +++ b/test/integration/examples_build.cc @@ -24,6 +24,7 @@ #include #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" // File copied from // https://github.com/ignitionrobotics/ign-gui/raw/ign-gui3/test/integration/ExamplesBuild_TEST.cc @@ -122,7 +123,8 @@ bool createAndSwitchToTempDir(std::string &_newTempPath) #endif ////////////////////////////////////////////////// -class ExamplesBuild : public ::testing::TestWithParam +class ExamplesBuild + : public InternalFixture<::testing::TestWithParam> { /// \brief Build code in a temporary build folder. /// \param[in] _type Type of example to build (plugins, standalone). diff --git a/test/integration/gpu_lidar.cc b/test/integration/gpu_lidar.cc index fa69df3b9d..a1f3368a43 100644 --- a/test/integration/gpu_lidar.cc +++ b/test/integration/gpu_lidar.cc @@ -28,6 +28,7 @@ #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" #define LASER_TOL 1e-4 @@ -35,15 +36,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test GpuLidarTest system -class GpuLidarTest : public ::testing::Test +class GpuLidarTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; std::mutex mutex; diff --git a/test/integration/imu_system.cc b/test/integration/imu_system.cc index f7ae7b65c2..68147f4e30 100644 --- a/test/integration/imu_system.cc +++ b/test/integration/imu_system.cc @@ -37,6 +37,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 @@ -44,15 +45,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test ImuTest system -class ImuTest : public ::testing::Test +class ImuTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; std::mutex mutex; diff --git a/test/integration/joint_controller_system.cc b/test/integration/joint_controller_system.cc index a773c404b2..eedb002305 100644 --- a/test/integration/joint_controller_system.cc +++ b/test/integration/joint_controller_system.cc @@ -32,6 +32,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 @@ -39,15 +40,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test fixture for JointController system -class JointControllerTestFixture : public ::testing::Test +class JointControllerTestFixture : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/joint_position_controller_system.cc b/test/integration/joint_position_controller_system.cc index 10a1a2dbb4..679293f582 100644 --- a/test/integration/joint_position_controller_system.cc +++ b/test/integration/joint_position_controller_system.cc @@ -32,6 +32,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 @@ -39,15 +40,9 @@ using namespace ignition; using namespace gazebo; /// \brief Test fixture for JointPositionController system -class JointPositionControllerTestFixture : public ::testing::Test +class JointPositionControllerTestFixture + : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/joint_state_publisher_system.cc b/test/integration/joint_state_publisher_system.cc index 64f7f3b16c..d58e59c522 100644 --- a/test/integration/joint_state_publisher_system.cc +++ b/test/integration/joint_state_publisher_system.cc @@ -22,21 +22,16 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; /// \brief Test JointStatePublisher system -class JointStatePublisherTest : public ::testing::TestWithParam +class JointStatePublisherTest + : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/kinetic_energy_monitor_system.cc b/test/integration/kinetic_energy_monitor_system.cc index bd5b1853ec..5a7fa43c5c 100644 --- a/test/integration/kinetic_energy_monitor_system.cc +++ b/test/integration/kinetic_energy_monitor_system.cc @@ -27,20 +27,14 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test Kinetic Energy Monitor system -class KineticEnergyMonitorTest : public ::testing::Test +class KineticEnergyMonitorTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); - } }; std::mutex mutex; diff --git a/test/integration/level_manager.cc b/test/integration/level_manager.cc index e61da0ed5a..f9c7e364d6 100644 --- a/test/integration/level_manager.cc +++ b/test/integration/level_manager.cc @@ -47,6 +47,7 @@ #include "ignition/gazebo/components/Pose.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; @@ -97,15 +98,12 @@ class ModelMover: public test::Relay }; ////////////////////////////////////////////////// -class LevelManagerFixture : public ::testing::Test +class LevelManagerFixture : public InternalFixture<::testing::Test> { // Documentation inherited protected: void SetUp() override { - common::Console::SetVerbosity(4); - - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); + InternalFixture::SetUp(); ignition::gazebo::ServerConfig serverConfig; diff --git a/test/integration/level_manager_runtime_performers.cc b/test/integration/level_manager_runtime_performers.cc index b873719afc..cb1ffedeb6 100644 --- a/test/integration/level_manager_runtime_performers.cc +++ b/test/integration/level_manager_runtime_performers.cc @@ -44,6 +44,7 @@ #include "plugins/MockSystem.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; @@ -94,15 +95,12 @@ class ModelMover: public test::Relay }; ////////////////////////////////////////////////// -class LevelManagerFixture : public ::testing::Test +class LevelManagerFixture : public InternalFixture<::testing::Test> { // Documentation inherited protected: void SetUp() override { - common::Console::SetVerbosity(4); - - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); + InternalFixture::SetUp(); ignition::gazebo::ServerConfig serverConfig; diff --git a/test/integration/lift_drag_system.cc b/test/integration/lift_drag_system.cc index 72ecf28d98..a03100f9cb 100644 --- a/test/integration/lift_drag_system.cc +++ b/test/integration/lift_drag_system.cc @@ -39,6 +39,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 @@ -46,15 +47,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test fixture for LiftDrag system -class LiftDragTestFixture : public ::testing::Test +class LiftDragTestFixture : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/link.cc b/test/integration/link.cc index 4b69e71c0c..72b361635b 100644 --- a/test/integration/link.cc +++ b/test/integration/link.cc @@ -38,15 +38,13 @@ #include #include +#include "../helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; -class LinkIntegrationTest : public ::testing::Test +class LinkIntegrationTest : public InternalFixture<::testing::Test> { - public: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - } }; ////////////////////////////////////////////////// diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 26e293cfdf..3b81bf8929 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -51,6 +51,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; @@ -150,16 +151,8 @@ void entryDiff(std::vector &_paths1, #endif ////////////////////////////////////////////////// -class LogSystemTest : public ::testing::Test +class LogSystemTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - // Create a temporary directory in build path for recorded data public: void CreateLogsDir() { diff --git a/test/integration/logical_audio_sensor_plugin.cc b/test/integration/logical_audio_sensor_plugin.cc index eac68bcb47..0d403402f0 100644 --- a/test/integration/logical_audio_sensor_plugin.cc +++ b/test/integration/logical_audio_sensor_plugin.cc @@ -39,20 +39,14 @@ #include "ignition/gazebo/Types.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test LogicalAudio system plugin -class LogicalAudioTest : public ::testing::Test +class LogicalAudioTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; TEST_F(LogicalAudioTest, LogicalAudioDetections) diff --git a/test/integration/logical_camera_system.cc b/test/integration/logical_camera_system.cc index 682356f0b5..32bae02ef5 100644 --- a/test/integration/logical_camera_system.cc +++ b/test/integration/logical_camera_system.cc @@ -33,20 +33,14 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test LogicalCameraTest system -class LogicalCameraTest : public ::testing::Test +class LogicalCameraTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; std::mutex mutex; diff --git a/test/integration/magnetometer_system.cc b/test/integration/magnetometer_system.cc index 85a702dd30..cf29f976f8 100644 --- a/test/integration/magnetometer_system.cc +++ b/test/integration/magnetometer_system.cc @@ -35,6 +35,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define TOL 1e-4 @@ -42,15 +43,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test MagnetometerTest system -class MagnetometerTest : public ::testing::Test +class MagnetometerTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; std::mutex mutex; diff --git a/test/integration/model.cc b/test/integration/model.cc index 378db68d7d..4ffa3cf594 100644 --- a/test/integration/model.cc +++ b/test/integration/model.cc @@ -34,15 +34,13 @@ #include #include +#include "../helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; -class ModelIntegrationTest : public ::testing::Test +class ModelIntegrationTest : public InternalFixture<::testing::Test> { - public: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - } }; ////////////////////////////////////////////////// diff --git a/test/integration/multicopter.cc b/test/integration/multicopter.cc index 54ce5bb5fb..f88789a531 100644 --- a/test/integration/multicopter.cc +++ b/test/integration/multicopter.cc @@ -40,21 +40,14 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; -class MulticopterTest : public ::testing::Test +class MulticopterTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - protected: std::unique_ptr StartServer(const std::string &_filePath) { ServerConfig serverConfig; diff --git a/test/integration/network_handshake.cc b/test/integration/network_handshake.cc index 830120e171..09b349e002 100644 --- a/test/integration/network_handshake.cc +++ b/test/integration/network_handshake.cc @@ -25,6 +25,8 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "../helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; @@ -59,13 +61,8 @@ uint64_t testPaused(bool _paused) } ///////////////////////////////////////////////// -class NetworkHandshake : public ::testing::Test +class NetworkHandshake : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/performer_detector.cc b/test/integration/performer_detector.cc index ec9cb04b1c..0ca0fc95dc 100644 --- a/test/integration/performer_detector.cc +++ b/test/integration/performer_detector.cc @@ -29,21 +29,14 @@ #include "ignition/gazebo/test_config.hh" #include "helpers/Relay.hh" +#include "helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; -class PerformerDetectorTest : public ::testing::Test +class PerformerDetectorTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - protected: std::unique_ptr StartServer(const std::string &_filePath, bool _useLevels = false) { diff --git a/test/integration/physics_system.cc b/test/integration/physics_system.cc index c0fe7c662f..f6d31c8436 100644 --- a/test/integration/physics_system.cc +++ b/test/integration/physics_system.cc @@ -57,20 +57,14 @@ #include "ignition/gazebo/components/World.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; -class PhysicsSystemFixture : public ::testing::Test +class PhysicsSystemFixture : public InternalFixture<::testing::Test> { - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - // 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()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/play_pause.cc b/test/integration/play_pause.cc index f277977e4e..92a9e6d398 100644 --- a/test/integration/play_pause.cc +++ b/test/integration/play_pause.cc @@ -24,6 +24,8 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "../helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; @@ -93,8 +95,12 @@ uint64_t iterations() return iterations; } +class PlayPause : public InternalFixture<::testing::Test> +{ +}; + ///////////////////////////////////////////////// -TEST(PlayPause, PlayPause) +TEST_F(PlayPause, PlayPause) { common::Console::SetVerbosity(4); diff --git a/test/integration/pose_publisher_system.cc b/test/integration/pose_publisher_system.cc index e210c00103..c7ebd095b6 100644 --- a/test/integration/pose_publisher_system.cc +++ b/test/integration/pose_publisher_system.cc @@ -33,6 +33,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define tol 10e-4 @@ -40,15 +41,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test PosePublisher system -class PosePublisherTest : public ::testing::TestWithParam +class PosePublisherTest : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; std::mutex mutex; diff --git a/test/integration/rgbd_camera.cc b/test/integration/rgbd_camera.cc index e971cfc871..3eed692ba3 100644 --- a/test/integration/rgbd_camera.cc +++ b/test/integration/rgbd_camera.cc @@ -29,6 +29,7 @@ #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" #define DEPTH_TOL 1e-4 @@ -36,15 +37,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test RgbdCameraTest system -class RgbdCameraTest : public ::testing::Test +class RgbdCameraTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; std::mutex mutex; diff --git a/test/integration/save_world.cc b/test/integration/save_world.cc index 149ce5c3f3..4142ed253c 100644 --- a/test/integration/save_world.cc +++ b/test/integration/save_world.cc @@ -38,18 +38,14 @@ #include "helpers/UniqueTestDirectoryEnv.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; ///////////////////////////////////////////////// -class SdfGeneratorFixture : public ::testing::Test +class SdfGeneratorFixture : public InternalFixture<::testing::Test> { - public: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - } - public: void LoadWorld(const std::string &_path) { ServerConfig serverConfig; diff --git a/test/integration/scene_broadcaster_system.cc b/test/integration/scene_broadcaster_system.cc index 1e46f8b645..31bdcfc0b3 100644 --- a/test/integration/scene_broadcaster_system.cc +++ b/test/integration/scene_broadcaster_system.cc @@ -27,18 +27,14 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" + using namespace ignition; /// \brief Test SceneBroadcaster system -class SceneBroadcasterTest : public ::testing::TestWithParam +class SceneBroadcasterTest + : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/sdf_frame_semantics.cc b/test/integration/sdf_frame_semantics.cc index 43a7501bef..9ca7890669 100644 --- a/test/integration/sdf_frame_semantics.cc +++ b/test/integration/sdf_frame_semantics.cc @@ -42,19 +42,13 @@ #include "ignition/gazebo/components/World.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; -class SdfFrameSemanticsTest : public ::testing::Test +class SdfFrameSemanticsTest : public InternalFixture<::testing::Test> { - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - public: void StartServer() { this->relay = std::make_unique(); diff --git a/test/integration/sdf_include.cc b/test/integration/sdf_include.cc index 29f9c222d8..7a19d30b5f 100644 --- a/test/integration/sdf_include.cc +++ b/test/integration/sdf_include.cc @@ -22,11 +22,17 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" // NOLINT(build/include) +#include "../helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; +class SdfInclude : public InternalFixture<::testing::Test> +{ +}; + ///////////////////////////////////////////////// -TEST(SdfInclude, DownloadFromFuel) +TEST_F(SdfInclude, DownloadFromFuel) { std::string path = common::cwd() + "/test_cache"; diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index a33aec55aa..661a92819e 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -40,20 +40,18 @@ #include "ignition/gazebo/components/World.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace std::chrono_literals; namespace components = ignition::gazebo::components; ////////////////////////////////////////////////// -class SensorsFixture : public ::testing::Test +class SensorsFixture : public InternalFixture> { protected: void SetUp() override { - common::Console::SetVerbosity(4); - // 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()); + InternalFixture::SetUp(); auto plugin = sm.LoadPlugin("libMockSystem.so", "ignition::gazebo::MockSystem", diff --git a/test/integration/thermal_system.cc b/test/integration/thermal_system.cc index ae69c7fcbf..3dac35cc2c 100644 --- a/test/integration/thermal_system.cc +++ b/test/integration/thermal_system.cc @@ -29,6 +29,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define tol 10e-4 @@ -36,15 +37,8 @@ using namespace ignition; using namespace gazebo; /// \brief Test Thermal system -class ThermalTest : public ::testing::Test +class ThermalTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/touch_plugin.cc b/test/integration/touch_plugin.cc index 856b1e6be7..90b4080c06 100644 --- a/test/integration/touch_plugin.cc +++ b/test/integration/touch_plugin.cc @@ -23,20 +23,14 @@ #include "ignition/gazebo/Server.hh" #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; /// \brief Test TouchPlugin system -class TouchPluginTest : public ::testing::Test +class TouchPluginTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - public: void StartServer(const std::string &_sdfFile) { ServerConfig serverConfig; diff --git a/test/integration/triggered_publisher.cc b/test/integration/triggered_publisher.cc index 436ad8b998..70201336ed 100644 --- a/test/integration/triggered_publisher.cc +++ b/test/integration/triggered_publisher.cc @@ -36,19 +36,19 @@ #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; -class TriggeredPublisherTest : public ::testing::Test +class TriggeredPublisherTest : public InternalFixture<::testing::Test> { // Documentation inherited protected: void SetUp() override { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); + InternalFixture::SetUp(); + // Start server ServerConfig serverConfig; const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + diff --git a/test/integration/user_commands.cc b/test/integration/user_commands.cc index 75dd18421a..04e537a71c 100644 --- a/test/integration/user_commands.cc +++ b/test/integration/user_commands.cc @@ -36,20 +36,14 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; ////////////////////////////////////////////////// -class UserCommandsTest : public ::testing::Test +class UserCommandsTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/velocity_control_system.cc b/test/integration/velocity_control_system.cc index 5eb7722440..392b2d6345 100644 --- a/test/integration/velocity_control_system.cc +++ b/test/integration/velocity_control_system.cc @@ -30,22 +30,16 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; using namespace std::chrono_literals; /// \brief Test VelocityControl system -class VelocityControlTest : public ::testing::TestWithParam +class VelocityControlTest + : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - /// \param[in] _sdfFile SDF file to load. /// \param[in] _cmdVelTopic Command velocity topic. protected: void TestPublishCmd(const std::string &_sdfFile, diff --git a/test/integration/wheel_slip.cc b/test/integration/wheel_slip.cc index ebc26042fa..6e931b02ea 100644 --- a/test/integration/wheel_slip.cc +++ b/test/integration/wheel_slip.cc @@ -49,20 +49,14 @@ #include "plugins/MockSystem.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test DiffDrive system -class WheelSlipTest : public ::testing::Test +class WheelSlipTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } /// \brief Class to hold parameters for tire tests. public: class WheelSlipState { diff --git a/test/integration/wind_effects.cc b/test/integration/wind_effects.cc index f91d0ce1c3..1bbee6e6f0 100644 --- a/test/integration/wind_effects.cc +++ b/test/integration/wind_effects.cc @@ -34,21 +34,14 @@ #include "ignition/gazebo/components/WindMode.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test WindEffects system -class WindEffectsTest : public ::testing::Test +class WindEffectsTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - ignition::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str()); - } - public: void StartServer(const std::string &_sdfFile) { ServerConfig serverConfig; diff --git a/test/integration/world.cc b/test/integration/world.cc index 84f76fcb01..9657d53eb7 100644 --- a/test/integration/world.cc +++ b/test/integration/world.cc @@ -40,15 +40,13 @@ #include #include +#include "../helpers/EnvTestFixture.hh" + using namespace ignition; using namespace gazebo; -class WorldIntegrationTest : public ::testing::Test +class WorldIntegrationTest : public InternalFixture<::testing::Test> { - public: void SetUp() override - { - ignition::common::Console::SetVerbosity(4); - } }; //////////////////////////////////////////////////