From 76c7b39f9df9988e81bca7edc6deba2565225e9c Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Wed, 11 Aug 2021 09:28:51 -0700 Subject: [PATCH 01/17] =?UTF-8?q?=F0=9F=8E=88=203.9.0~pre2=20(#967)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- CMakeLists.txt | 4 ++-- Changelog.md | 56 +++++++++++++++++++++++++++++++++++++++++++++++++- 2 files changed, 57 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1b8ef5601f0..ddc65c6fb4e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ find_package(ignition-cmake2 2.8.0 REQUIRED) #============================================================================ # Configure the project #============================================================================ -ign_configure_project(VERSION_SUFFIX pre1) +ign_configure_project(VERSION_SUFFIX pre2) #============================================================================ # Set project-specific options @@ -40,7 +40,7 @@ endif() # This option is needed to use the PROTOBUF_GENERATE_CPP # in case protobuf is found with the CMake config files -# It needs to be set before any find_package(...) call +# It needs to be set before any find_package(...) call # as protobuf could be find transitively by any dependency set(protobuf_MODULE_COMPATIBLE TRUE) diff --git a/Changelog.md b/Changelog.md index 0578ea555d2..e8d70ce3c73 100644 --- a/Changelog.md +++ b/Changelog.md @@ -3,7 +3,61 @@ ### Ignition Gazebo 3.X.X (202X-XX-XX) -### Ignition Gazebo 3.9.0 (2021-07-XX) +### Ignition Gazebo 3.9.0 (2021-08-XX) + +1. Be more specific when looking for physics plugins + * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) + +1. Drag and drop meshes into scene + * [Pull request #939](https://github.com/ignitionrobotics/ign-gazebo/pull/939) + +1. Set protobuf_MODULE_COMPATIBLE before any find_package call + * [Pull request #957](https://github.com/ignitionrobotics/ign-gazebo/pull/957) + +1. [DiffDrive] add enable/disable + * [Pull request #772](https://github.com/ignitionrobotics/ign-gazebo/pull/772) + +1. Fix component inspector shutdown crash + * [Pull request #724](https://github.com/ignitionrobotics/ign-gazebo/pull/724) + +1. Add UserCommands Plugin. + * [Pull request #719](https://github.com/ignitionrobotics/ign-gazebo/pull/719) + +1. Setting the intiial velocity for a model or joint + * [Pull request #693](https://github.com/ignitionrobotics/ign-gazebo/pull/693) + +1. Examples and tutorial on using rendering API from plugins + * [Pull request #596](https://github.com/ignitionrobotics/ign-gazebo/pull/596) + +1. Add missing IGNITION_GAZEBO_VISIBLE macros + * [Pull request #563](https://github.com/ignitionrobotics/ign-gazebo/pull/563) + +1. Fix visibility macro names when used by a different component (Windows) + * [Pull request #564](https://github.com/ignitionrobotics/ign-gazebo/pull/564) + +1. No install apt recommends and clear cache + * [Pull request #423](https://github.com/ignitionrobotics/ign-gazebo/pull/423) + +1. Add 25percent darker view angle icons + * [Pull request #426](https://github.com/ignitionrobotics/ign-gazebo/pull/426) + +1. Expose a test fixture helper class + * [Pull request #926](https://github.com/ignitionrobotics/ign-gazebo/pull/926) + +1. Fix logic to disable server default plugins loading + * [Pull request #953](https://github.com/ignitionrobotics/ign-gazebo/pull/953) + +1. removed unneeded plugin update + * [Pull request #944](https://github.com/ignitionrobotics/ign-gazebo/pull/944) + +1. Functions to enable velocity and acceleration checks on Link + * [Pull request #935](https://github.com/ignitionrobotics/ign-gazebo/pull/935) + +1. Support adding systems that don't come from a plugin + * [Pull request #936](https://github.com/ignitionrobotics/ign-gazebo/pull/936) + +1. 3D plot GUI plugin + * [Pull request #917](https://github.com/ignitionrobotics/ign-gazebo/pull/917) 1. Add a convenience function for getting possibly non-existing components. * [Pull request #629](https://github.com/ignitionrobotics/ign-gazebo/pull/629) From 9691622cee754b156257214a014ca4d7b5a4fec2 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 12 Aug 2021 19:29:17 -0700 Subject: [PATCH 02/17] Fix entity creation console msg (#972) Signed-off-by: Ian Chen --- examples/standalone/entity_creation/entity_creation.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/standalone/entity_creation/entity_creation.cc b/examples/standalone/entity_creation/entity_creation.cc index 6184f1beef3..ff7a2c980e8 100644 --- a/examples/standalone/entity_creation/entity_creation.cc +++ b/examples/standalone/entity_creation/entity_creation.cc @@ -79,7 +79,7 @@ void createEntityFromStr(const std::string modelStr) if (executed) { if (result) - std::cout << "Sphere was created : [" << res.data() << "]" << std::endl; + std::cout << "Entity was created : [" << res.data() << "]" << std::endl; else { std::cout << "Service call failed" << std::endl; From 4a5a33dca43aa12ad84453082125f9d6ab1bf47b Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 13 Aug 2021 14:53:46 -0700 Subject: [PATCH 03/17] 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 1f762704367..68957a503ff 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 98899d3e8a1..ea3bdd40a47 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 22c61b4e7c8..824d30758b4 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 4794c44a55b..f6f3053d261 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 7e834a61581..c4bbe58a31a 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 fc3bb6d1226..e6e7ee2b4fe 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 22dc0848dda..580c0d11c77 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 89e8c903875..8cce7b011dc 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 0048f1e15bd..49000a8471e 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 244e5b1846a..4c6d244f872 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 7b117cdeda1..c683faaec8f 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 703fa7de845..72aa9b14cf4 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 f34e6004092..6e085c3b345 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 9b842031b51..79c5314a877 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 00000000000..e73636f6ac5 --- /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 be8e2d95f3d..51e9000d902 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 59588881273..4b391963ac8 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 cc309c3119a..c8423e88ae4 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 bd894299df4..53f09d21531 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 b458130b927..ed79d6eef6d 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 41c7d530ec4..77445fdd61b 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 07968ccfea8..e21b71fc985 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 ae677413c03..891c448870e 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 20ae6a89e2f..3991468b6b9 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 589c3ff3c0c..0a9014673b9 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 9ecbe5aacd3..c5d50777eb7 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 53ed104f31f..bbbe91c66f7 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 d1b444ff101..e3a0081fa52 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 a7a88639bb9..780e210250b 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 bb017612a4c..f75da52514b 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 34e95990dfb..b71fb4de525 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 d6c43d97500..bf40f70614f 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 fa69df3b9d8..a1f3368a430 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 f7ae7b65c21..68147f4e30d 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 a773c404b28..eedb0023058 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 10a1a2dbb48..679293f582a 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 64f7f3b16cf..d58e59c522b 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 bd5b1853eca..5a7fa43c5ce 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 e61da0ed5ad..f9c7e364d69 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 b873719afc0..cb1ffedeb64 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 72ecf28d981..a03100f9cbf 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 4b69e71c0cd..72b361635ba 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 26e293cfdf4..3b81bf89290 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 eac68bcb475..0d403402f04 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 682356f0b5f..32bae02ef53 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 85a702dd303..cf29f976f8f 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 378db68d7dd..4ffa3cf5949 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 54ce5bb5fb2..f88789a5319 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 830120e171e..09b349e002e 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 ec9cb04b1cb..0ca0fc95dcd 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 c0fe7c662fd..f6d31c8436c 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 f277977e4ef..92a9e6d3989 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 e210c001036..c7ebd095b62 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 e971cfc8716..3eed692ba34 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 149ce5c3f39..4142ed253c0 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 1e46f8b6453..31bdcfc0b35 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 43a7501bef1..9ca7890669b 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 29f9c222d8b..7a19d30b5fb 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 a33aec55aa6..661a92819e3 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 ae69c7fcbfa..3dac35cc2c8 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 856b1e6be7e..90b4080c064 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 436ad8b9983..70201336edb 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 75dd18421ab..04e537a71cc 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 5eb77224404..392b2d63456 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 ebc26042fa2..6e931b02ea8 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 f91d0ce1c3e..1bbee6e6f0a 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 84f76fcb018..9657d53eb77 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); - } }; ////////////////////////////////////////////////// From d00a48e33ff681aee38e5599b0957991d0d6a704 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Fri, 13 Aug 2021 15:14:57 -0700 Subject: [PATCH 04/17] Updates when forward-porting to v4 (#973) Signed-off-by: Louise Poubel --- src/ServerPrivate.cc | 2 -- src/gui/Gui_TEST.cc | 8 +++++++- test/integration/ackermann_steering_system.cc | 12 +++--------- test/integration/follow_actor_system.cc | 10 ++-------- test/integration/fuel_cached_server.cc | 10 ++++++++-- test/integration/halt_motion.cc | 11 ++--------- .../joint_trajectory_controller_system.cc | 12 +++--------- test/integration/multiple_servers.cc | 11 ++++++++--- test/integration/odometry_publisher.cc | 12 +++--------- test/integration/optical_tactile_plugin.cc | 11 ++--------- test/integration/particle_emitter.cc | 10 ++-------- test/integration/particle_emitter2.cc | 10 ++-------- test/integration/thermal_sensor_system.cc | 10 ++-------- 13 files changed, 44 insertions(+), 85 deletions(-) diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 98146d71b62..24986300722 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -234,8 +234,6 @@ void ServerPrivate::AddRecordPlugin(const ServerConfig &_config) if (sdfUseLogRecord) { - bool hasCompress {false}; - bool sdfCompress; std::tie(sdfRecordResources, hasRecordResources) = recordPluginElem->Get("record_resources", false); diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc index 7c61a211dc3..96bd3c952bd 100644 --- a/src/gui/Gui_TEST.cc +++ b/src/gui/Gui_TEST.cc @@ -28,15 +28,21 @@ #include "ignition/gazebo/gui/Gui.hh" #include "ignition/gazebo/test_config.hh" +#include "../../test/helpers/EnvTestFixture.hh" + int gg_argc = 1; char **gg_argv = new char *[gg_argc]; using namespace ignition; using namespace gazebo; +class GuiTest : public InternalFixture<::testing::Test> +{ +}; + ///////////////////////////////////////////////// // https://github.com/ignitionrobotics/ign-gazebo/issues/8 -TEST(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager)) +TEST_F(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager)) { common::Console::SetVerbosity(4); igndbg << "Start test" << std::endl; diff --git a/test/integration/ackermann_steering_system.cc b/test/integration/ackermann_steering_system.cc index a4279b242f9..28a47cbf8e2 100644 --- a/test/integration/ackermann_steering_system.cc +++ b/test/integration/ackermann_steering_system.cc @@ -27,6 +27,7 @@ #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" #define tol 10e-4 @@ -36,16 +37,9 @@ using namespace gazebo; using namespace std::chrono_literals; /// \brief Test AckermannSteering system -class AckermannSteeringTest : public ::testing::TestWithParam +class AckermannSteeringTest + : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); - } - /// \param[in] _sdfFile SDF file to load. /// \param[in] _cmdVelTopic Command velocity topic. /// \param[in] _odomTopic Odometry topic. diff --git a/test/integration/follow_actor_system.cc b/test/integration/follow_actor_system.cc index 566384f1bfd..adddf0a0765 100644 --- a/test/integration/follow_actor_system.cc +++ b/test/integration/follow_actor_system.cc @@ -28,6 +28,7 @@ #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" #define tol 10e-4 @@ -36,15 +37,8 @@ using namespace gazebo; using namespace std::chrono_literals; /// \brief Test FollowActor system -class FollowActorTest : public ::testing::TestWithParam +class FollowActorTest : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); - } }; class Relay diff --git a/test/integration/fuel_cached_server.cc b/test/integration/fuel_cached_server.cc index 7003459ff75..5be773871ab 100644 --- a/test/integration/fuel_cached_server.cc +++ b/test/integration/fuel_cached_server.cc @@ -27,7 +27,12 @@ using namespace ignition::gazebo; using namespace std::chrono_literals; ///////////////////////////////////////////////// -TEST_P(ServerFixture, CachedFuelWorld) +class FuelCachedServer : public InternalFixture<::testing::TestWithParam> +{ +}; + +///////////////////////////////////////////////// +TEST_P(FuelCachedServer, CachedFuelWorld) { auto cachedWorldPath = common::joinPaths(std::string(PROJECT_SOURCE_PATH), "test", "worlds"); @@ -54,4 +59,5 @@ TEST_P(ServerFixture, CachedFuelWorld) // 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)); +INSTANTIATE_TEST_SUITE_P(ServerRepeat, FuelCachedServer, + ::testing::Range(1, 2)); diff --git a/test/integration/halt_motion.cc b/test/integration/halt_motion.cc index ec3b6c01593..2564e1513b8 100644 --- a/test/integration/halt_motion.cc +++ b/test/integration/halt_motion.cc @@ -29,6 +29,7 @@ #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" #define tol 10e-4 @@ -38,16 +39,8 @@ using namespace gazebo; using namespace std::chrono_literals; /// \brief Test DiffDrive system -class HaltMotionTest : public ::testing::TestWithParam +class HaltMotionTest : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(1); - 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/joint_trajectory_controller_system.cc b/test/integration/joint_trajectory_controller_system.cc index 70ca0aad3f6..b2c4bdeaa32 100644 --- a/test/integration/joint_trajectory_controller_system.cc +++ b/test/integration/joint_trajectory_controller_system.cc @@ -32,6 +32,7 @@ #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" #define TOL 1e-4 @@ -40,16 +41,9 @@ using namespace ignition; using namespace gazebo; /// \brief Test fixture for JointTrajectoryController system -class JointTrajectoryControllerTestFixture : public ::testing::Test +class JointTrajectoryControllerTestFixture + : 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); - } }; ///////////////////////////////////////////////// diff --git a/test/integration/multiple_servers.cc b/test/integration/multiple_servers.cc index 71f89ab663e..05516c790b9 100644 --- a/test/integration/multiple_servers.cc +++ b/test/integration/multiple_servers.cc @@ -27,7 +27,12 @@ using namespace ignition::gazebo; using namespace std::chrono_literals; ///////////////////////////////////////////////// -TEST_P(ServerFixture, TwoServersNonBlocking) +class MultipleServers : public InternalFixture<::testing::TestWithParam> +{ +}; + +///////////////////////////////////////////////// +TEST_P(MultipleServers, TwoServersNonBlocking) { ignition::gazebo::ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); @@ -67,7 +72,7 @@ TEST_P(ServerFixture, TwoServersNonBlocking) } ///////////////////////////////////////////////// -TEST_P(ServerFixture, TwoServersMixedBlocking) +TEST_P(MultipleServers, TwoServersMixedBlocking) { ignition::gazebo::ServerConfig serverConfig; serverConfig.SetSdfString(TestWorldSansPhysics::World()); @@ -101,4 +106,4 @@ TEST_P(ServerFixture, TwoServersMixedBlocking) // 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)); +INSTANTIATE_TEST_SUITE_P(ServerRepeat, MultipleServers, ::testing::Range(1, 2)); diff --git a/test/integration/odometry_publisher.cc b/test/integration/odometry_publisher.cc index 1488dbd14ec..0e329b54c3e 100644 --- a/test/integration/odometry_publisher.cc +++ b/test/integration/odometry_publisher.cc @@ -32,6 +32,7 @@ #include "ignition/gazebo/test_config.hh" #include "../helpers/Relay.hh" +#include "../helpers/EnvTestFixture.hh" #define tol 0.005 @@ -40,16 +41,9 @@ using namespace gazebo; using namespace std::chrono_literals; /// \brief Test OdometryPublisher system -class OdometryPublisherTest : public ::testing::TestWithParam +class OdometryPublisherTest + : public InternalFixture<::testing::TestWithParam> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); - } - /// \param[in] _sdfFile SDF file to load. /// \param[in] _odomTopic Odometry topic. protected: void TestMovement(const std::string &_sdfFile, diff --git a/test/integration/optical_tactile_plugin.cc b/test/integration/optical_tactile_plugin.cc index 45ac53609c5..bab4228a30b 100644 --- a/test/integration/optical_tactile_plugin.cc +++ b/test/integration/optical_tactile_plugin.cc @@ -32,21 +32,14 @@ #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" +#include "../helpers/EnvTestFixture.hh" using namespace ignition; using namespace gazebo; /// \brief Test OpticalTactilePlugin system -class OpticalTactilePluginTest : public ::testing::Test +class OpticalTactilePluginTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); - } - public: void StartServer(const std::string &_sdfFile) { ServerConfig serverConfig; diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index b5f4b091bef..ff9826bb224 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -30,20 +30,14 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/test_config.hh" +#include "helpers/EnvTestFixture.hh" #include "helpers/Relay.hh" using namespace ignition; using namespace gazebo; -class ParticleEmitterTest : public ::testing::Test +class ParticleEmitterTest : 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); - } public: void LoadWorld(const std::string &_path, bool _useLevels = false) { this->serverConfig.SetSdfFile( diff --git a/test/integration/particle_emitter2.cc b/test/integration/particle_emitter2.cc index dace3704c0f..826f51b2a27 100644 --- a/test/integration/particle_emitter2.cc +++ b/test/integration/particle_emitter2.cc @@ -30,20 +30,14 @@ #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/test_config.hh" +#include "helpers/EnvTestFixture.hh" #include "helpers/Relay.hh" using namespace ignition; using namespace gazebo; -class ParticleEmitter2Test : public ::testing::Test +class ParticleEmitter2Test : 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); - } public: void LoadWorld(const std::string &_path, bool _useLevels = false) { this->serverConfig.SetSdfFile( diff --git a/test/integration/thermal_sensor_system.cc b/test/integration/thermal_sensor_system.cc index 4e799193a40..aa8fe4e5163 100644 --- a/test/integration/thermal_sensor_system.cc +++ b/test/integration/thermal_sensor_system.cc @@ -34,21 +34,15 @@ #include "ignition/gazebo/SystemLoader.hh" #include "ignition/gazebo/test_config.hh" +#include "../helpers/EnvTestFixture.hh" #include "../helpers/Relay.hh" using namespace ignition; using namespace gazebo; /// \brief Test Thermal system -class ThermalSensorTest : public ::testing::Test +class ThermalSensorTest : public InternalFixture<::testing::Test> { - // Documentation inherited - protected: void SetUp() override - { - common::Console::SetVerbosity(4); - setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH", - (std::string(PROJECT_BINARY_PATH) + "/lib").c_str(), 1); - } }; From 7d1a3e09dc596a4bbee968a955949b55b08629cd Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Mon, 16 Aug 2021 00:34:44 -0700 Subject: [PATCH 05/17] Entity tree: prevent creation of repeated entity items (#974) Signed-off-by: Louise Poubel --- src/gui/plugins/entity_tree/EntityTree.cc | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/gui/plugins/entity_tree/EntityTree.cc b/src/gui/plugins/entity_tree/EntityTree.cc index 8a0ae74152c..79de5dfb7f2 100644 --- a/src/gui/plugins/entity_tree/EntityTree.cc +++ b/src/gui/plugins/entity_tree/EntityTree.cc @@ -132,6 +132,13 @@ void TreeModel::AddEntity(unsigned int _entity, const QString &_entityName, return; } + if (this->entityItems.find(_entity) != this->entityItems.end()) + { + ignwarn << "Internal error: Trying to create item for entity [" << _entity + << "], but entity already has an item." << std::endl; + return; + } + // New entity item auto entityItem = new QStandardItem(_entityName); entityItem->setData(_entityName, this->roleNames().key("entityName")); From d468c05decf017cabb765f3943559a8bb7db3e14 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 19 Aug 2021 19:42:48 +0200 Subject: [PATCH 06/17] Removed unused variable in Shapes plugin (#984) Signed-off-by: ahcorde --- src/gui/plugins/shapes/Shapes.cc | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/gui/plugins/shapes/Shapes.cc b/src/gui/plugins/shapes/Shapes.cc index 3b9165e5e3a..dc00229760c 100644 --- a/src/gui/plugins/shapes/Shapes.cc +++ b/src/gui/plugins/shapes/Shapes.cc @@ -40,9 +40,6 @@ namespace ignition::gazebo /// \brief Ignition communication node. public: transport::Node node; - /// \brief Mutex to protect mode - public: std::mutex mutex; - /// \brief Transform control service name public: std::string service; }; From 054ff128564ca635b214eaa3e4dc2f34ebeca48a Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 24 Aug 2021 01:52:15 -0700 Subject: [PATCH 07/17] =?UTF-8?q?=F0=9F=8E=88=203.9.0=20(#976)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- CMakeLists.txt | 2 +- Changelog.md | 8 +++++++- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ddc65c6fb4e..5047ec19a13 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,7 +14,7 @@ find_package(ignition-cmake2 2.8.0 REQUIRED) #============================================================================ # Configure the project #============================================================================ -ign_configure_project(VERSION_SUFFIX pre2) +ign_configure_project(VERSION_SUFFIX) #============================================================================ # Set project-specific options diff --git a/Changelog.md b/Changelog.md index e8d70ce3c73..5ea674b9d87 100644 --- a/Changelog.md +++ b/Changelog.md @@ -3,7 +3,13 @@ ### Ignition Gazebo 3.X.X (202X-XX-XX) -### Ignition Gazebo 3.9.0 (2021-08-XX) +### Ignition Gazebo 3.9.0 (2021-08-16) + +1. Entity tree: prevent creation of repeated entity items + * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974) + +1. Don't use $HOME on most tests (InternalFixture) + * [Pull request #971](https://github.com/ignitionrobotics/ign-gazebo/pull/971) 1. Be more specific when looking for physics plugins * [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965) From d94d58538a7a6fd2d432638b7a3874a431473198 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 24 Aug 2021 15:29:32 -0700 Subject: [PATCH 08/17] =?UTF-8?q?=F0=9F=91=A9=E2=80=8D=F0=9F=8C=BE=20Remov?= =?UTF-8?q?e=20bitbucket-pipelines.yml=20(#991)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Louise Poubel --- bitbucket-pipelines.yml | 100 ---------------------------------------- 1 file changed, 100 deletions(-) delete mode 100644 bitbucket-pipelines.yml diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml deleted file mode 100644 index 30fd50bfea2..00000000000 --- a/bitbucket-pipelines.yml +++ /dev/null @@ -1,100 +0,0 @@ -image: ubuntu:bionic - -pipelines: - default: - - step: - script: - - apt-get update - - apt -y install wget lsb-release gnupg sudo curl - # Enable relevant package repositories - - docker/scripts/enable_ign_stable.sh - - docker/scripts/enable_ign_prerelease.sh - # Install base dependencies - - docker/scripts/install_common_deps.sh - - docker/scripts/enable_gcc8.sh - - docker/scripts/install_ign_deps.sh - # There are two methods to install ignition/osrf dependencies. - # The first method uses debians and the second builds dependencies - # from source. For each dependency, please use only one method. - # METHOD 1: Install the following debians - - apt-get install -y - libignition-cmake2-dev - libignition-common3-dev - libignition-gui3-dev - libignition-math6-eigen3-dev - libignition-msgs5-dev - libignition-plugin-dev - libignition-rendering3-dev - libignition-tools-dev - libignition-transport8-dev - libsdformat9-dev - libignition-fuel-tools4-dev - libignition-physics2-dev - libignition-sensors3-dev - # METHOD 2: Build from source - # Build dependencies from source using a given branch - # - docker/scripts/build_ign.sh ignitionrobotics ign-sensors default - # - docker/scripts/build_ign.sh ignitionrobotics ign-physics default - # - docker/scripts/build_ign.sh ignitionrobotics ign-fuel-tools default - # Build Ignition Gazebo - - ./tools/clang_tidy.sh - - mkdir build - - cd build - - cmake .. -DCMAKE_BUILD_TYPE=coverage - - make -j1 install - - export IGN_CONFIG_PATH=/usr/local/share/ignition - - export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/usr/local/lib - # run codecheck before tests so flaky tests don't obscure codecheck failures - - make codecheck - - export CTEST_OUTPUT_ON_FAILURE=1 - - make test - - make coverage - # Use a special version of codecov for handling gcc8 output. - - bash <(curl -s https://raw.githubusercontent.com/codecov/codecov-bash/4678d212cce2078bbaaf5027af0c0dafaad6a095/codecov) -X gcovout -X gcov - custom: - benchmark: - - step: - script: - - apt-get update - - apt -y install wget lsb-release gnupg sudo curl - # Enable relevant package repositories - - docker/scripts/enable_ign_stable.sh - # Install base dependencies - - docker/scripts/install_common_deps.sh - - docker/scripts/enable_gcc8.sh - - docker/scripts/install_ign_deps.sh - # There are two methods to install ignition/osrf dependencies. - # The first method uses debians and the second builds dependencies - # from source. For each dependency, please use only one method. - # METHOD 1: Install the following debians - - apt-get install -y - libignition-cmake2-dev - libignition-common3-dev - libignition-math6-eigen3-dev - libignition-plugin-dev - libignition-tools-dev - # libignition-fuel-tools4-dev - # libignition-physics2-dev - # libsdformat9-dev - # libignition-gui3-dev - # libignition-msgs5-dev - # libignition-rendering3-dev - # libignition-sensors3-dev - # libignition-transport8-dev - # Build some Ignition libraries from source. - # Build ign-rendering from source using the default branch - - docker/scripts/build_ign.sh osrf sdformat default - - docker/scripts/build_ign.sh ignitionrobotics ign-msgs default - - docker/scripts/build_ign.sh ignitionrobotics ign-transport default - - docker/scripts/build_ign.sh ignitionrobotics ign-rendering default - - docker/scripts/build_ign.sh ignitionrobotics ign-gui default - - docker/scripts/build_ign.sh ignitionrobotics ign-sensors default - - docker/scripts/build_ign.sh ignitionrobotics ign-physics default - - docker/scripts/build_ign.sh ignitionrobotics ign-fuel-tools default - # Build Ignition Gazebo - - mkdir build - - cd build - - cmake .. - - make -j4 install - - ./bin/BENCHMARK_each --benchmark_out_format=json --benchmark_out=each.json - - ../docker/scripts/upload_json_benchmark.sh each.json From c6255868c7f39cc968f05f564aec31e09115641f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 26 Aug 2021 11:42:11 +0200 Subject: [PATCH 09/17] Improved doxygen (#996) * Improved doxygen Signed-off-by: ahcorde * Improved docs Signed-off-by: ahcorde --- CMakeLists.txt | 1 + include/ignition/gazebo/Conversions.hh | 96 ++++++++++++------- .../ignition/gazebo/EntityComponentManager.hh | 29 +++--- include/ignition/gazebo/Events.hh | 2 +- include/ignition/gazebo/Server.hh | 16 ++-- include/ignition/gazebo/ServerConfig.hh | 16 ++-- include/ignition/gazebo/Util.hh | 2 +- .../ignition/gazebo/components/Component.hh | 13 ++- .../gazebo/components/ContactSensor.hh | 2 +- include/ignition/gazebo/components/Factory.hh | 12 +-- .../gazebo/components/LogicalCamera.hh | 2 +- .../gazebo/components/Serialization.hh | 2 +- include/ignition/gazebo/gui/GuiSystem.hh | 9 +- .../ignition/gazebo/rendering/RenderUtil.hh | 4 +- .../ignition/gazebo/rendering/SceneManager.hh | 6 +- src/gui/plugins/align_tool/AlignTool.hh | 2 +- src/gui/plugins/modules/EntityContextMenu.hh | 1 - .../resource_spawner/ResourceSpawner.hh | 4 +- src/gui/plugins/scene3d/Scene3D.hh | 14 +-- .../battery_plugin/LinearBatteryPlugin.hh | 28 +++--- src/systems/breadcrumbs/Breadcrumbs.hh | 50 +++++----- src/systems/buoyancy/Buoyancy.hh | 2 +- .../CameraVideoRecorder.hh | 9 +- .../detachable_joint/DetachableJoint.hh | 10 +- .../log_video_recorder/LogVideoRecorder.hh | 16 ++-- .../LogicalAudioSensorPlugin.hh | 76 ++++++++------- .../MulticopterVelocityControl.hh | 4 +- .../performer_detector/PerformerDetector.hh | 4 +- src/systems/physics/EntityFeatureMap.hh | 4 +- src/systems/touch_plugin/TouchPlugin.hh | 25 ++--- .../triggered_publisher/TriggeredPublisher.hh | 15 +-- src/systems/wind_effects/WindEffects.hh | 20 ++-- tutorials/distributed_simulation.md | 3 +- 33 files changed, 273 insertions(+), 226 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5047ec19a13..9de8c4920b5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -178,6 +178,7 @@ if (NOT APPLE) API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md" TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md" ADDITIONAL_INPUT_DIRS "${CMAKE_SOURCE_DIR}/src/systems ${CMAKE_SOURCE_DIR}/src/gui/plugins" + IMAGE_PATH_DIRS "${CMAKE_SOURCE_DIR}/tutorials/files" TAGFILES "${IGNITION-MATH_DOXYGEN_TAGFILE} = ${IGNITION-MATH_API_URL}" "${IGNITION-MSGS_DOXYGEN_TAGFILE} = ${IGNITION-MSGS_API_URL}" diff --git a/include/ignition/gazebo/Conversions.hh b/include/ignition/gazebo/Conversions.hh index 27dda6b76de..13f079bff97 100644 --- a/include/ignition/gazebo/Conversions.hh +++ b/include/ignition/gazebo/Conversions.hh @@ -88,8 +88,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Geometry &/*_in*/) + Out convert(const sdf::Geometry &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -105,8 +106,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Pose &/*_in*/) + Out convert(const msgs::Pose &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -121,8 +123,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Geometry &/*_in*/) + Out convert(const msgs::Geometry &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -138,8 +141,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Material &/*_in*/) + Out convert(const sdf::Material &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -155,8 +159,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Material &/*_in*/) + Out convert(const msgs::Material &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -172,8 +177,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Actor &/*_in*/) + Out convert(const sdf::Actor &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -189,8 +195,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Actor& /*_in*/) + Out convert(const msgs::Actor& _in) { + (void)_in; Out::ConversionNotImplemented; } @@ -206,8 +213,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Light &/*_in*/) + Out convert(const sdf::Light &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -224,8 +232,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Light& /*_in*/) + Out convert(const msgs::Light& _in) { + (void)_in; Out::ConversionNotImplemented; } @@ -241,8 +250,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Gui &/*_in*/) + Out convert(const sdf::Gui &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -257,8 +267,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const std::chrono::steady_clock::duration &/*_in*/) + Out convert(const std::chrono::steady_clock::duration &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -274,8 +285,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Time &/*_in*/) + Out convert(const msgs::Time &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -291,8 +303,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const math::Inertiald &/*_in*/) + Out convert(const math::Inertiald &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -308,8 +321,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Inertial &/*_in*/) + Out convert(const msgs::Inertial &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -325,8 +339,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::JointAxis &/*_in*/) + Out convert(const sdf::JointAxis &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -342,8 +357,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Axis &/*_in*/) + Out convert(const msgs::Axis &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -359,8 +375,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Scene &/*_in*/) + Out convert(const sdf::Scene &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -375,8 +392,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Scene &/*_in*/) + Out convert(const msgs::Scene &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -392,8 +410,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Atmosphere &/*_in*/) + Out convert(const sdf::Atmosphere &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -409,8 +428,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Atmosphere &/*_in*/) + Out convert(const msgs::Atmosphere &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -427,8 +447,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Physics &/*_in*/) + Out convert(const sdf::Physics &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -444,8 +465,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Physics &/*_in*/) + Out convert(const msgs::Physics &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -462,8 +484,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Sensor &/*_in*/) + Out convert(const sdf::Sensor &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -479,8 +502,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Sensor &/*_in*/) + Out convert(const msgs::Sensor &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -496,8 +520,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::SensorNoise &/*_in*/) + Out convert(const msgs::SensorNoise &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -514,8 +539,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::WorldStatistics &/*_in*/) + Out convert(const msgs::WorldStatistics &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -531,8 +557,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const UpdateInfo &/*_in*/) + Out convert(const UpdateInfo &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -548,8 +575,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const sdf::Collision &/*_in*/) + Out convert(const sdf::Collision &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -565,8 +593,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::Collision &/*_in*/) + Out convert(const msgs::Collision &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -582,8 +611,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const std::string &/*_in*/) + Out convert(const std::string &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -598,8 +628,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const math::AxisAlignedBox &/*_in*/) + Out convert(const math::AxisAlignedBox &_in) { + (void)_in; Out::ConversionNotImplemented; } @@ -616,8 +647,9 @@ namespace ignition /// \return Conversion result. /// \tparam Out Output type. template - Out convert(const msgs::AxisAlignedBox &/*_in*/) + Out convert(const msgs::AxisAlignedBox &_in) { + (void)_in; Out::ConversionNotImplemented; } diff --git a/include/ignition/gazebo/EntityComponentManager.hh b/include/ignition/gazebo/EntityComponentManager.hh index 7e9c77b00cb..dc5ed1dce8f 100644 --- a/include/ignition/gazebo/EntityComponentManager.hh +++ b/include/ignition/gazebo/EntityComponentManager.hh @@ -81,7 +81,7 @@ namespace ignition /// into a queue. The queue is processed toward the end of a simulation /// update step. /// - /// \detail It is recommended that systems don't call this function + /// \details It is recommended that systems don't call this function /// directly, and instead use the `gazebo::SdfEntityCreator` class to /// remove entities. /// @@ -102,7 +102,7 @@ namespace ignition public: bool HasEntity(const Entity _entity) const; /// \brief Get the first parent of the given entity. - /// \detail Entities are not expected to have multiple parents. + /// \details Entities are not expected to have multiple parents. /// TODO(louise) Either prevent multiple parents or provide full support /// for multiple parents. /// \param[in] _entity Entity. @@ -111,11 +111,13 @@ namespace ignition /// \brief Set the parent of an entity. /// - /// \detail It is recommended that systems don't call this function + /// \details It is recommended that systems don't call this function /// directly, and instead use the `gazebo::SdfEntityCreator` class to /// create entities that have the correct parent-child relationship. /// - /// \param[in] _entity Entity or kNullEntity to remove current parent. + /// \param[in] _child Entity to set the parent + /// \param[in] _parent Entity which should be an immediate parent _child + /// entity. /// \return True if successful. Will fail if entities don't exist. public: bool SetParentEntity(const Entity _child, const Entity _parent); @@ -278,7 +280,7 @@ namespace ignition /// auto entity = EntityByComponents(components::Name("name"), /// components::Model()); /// - /// \detail Component type must have inequality operator. + /// \details Component type must have inequality operator. /// /// \param[in] _desiredComponents All the components which must match. /// \return Entity or kNullEntity if no entity has the exact components. @@ -293,7 +295,7 @@ namespace ignition /// auto entities = EntitiesByComponents(components::Name("camera"), /// components::Sensor()); /// - /// \detail Component type must have inequality operator. + /// \details Component type must have inequality operator. /// /// \param[in] _desiredComponents All the components which must match. /// \return All matching entities, or an empty vector if no child entity @@ -310,7 +312,7 @@ namespace ignition /// /// auto entity = ChildrenByComponents(parent, 123, std::string("name")); /// - /// \detail Component type must have inequality operator. + /// \details Component type must have inequality operator. /// /// \param[in] _parent Entity which should be an immediate parent of the /// returned entity. @@ -465,7 +467,7 @@ namespace ignition /// \brief Get a message with the serialized state of the given entities /// and components. - /// \detail The header of the message will not be populated, it is the + /// \details The header of the message will not be populated, it is the /// responsibility of the caller to timestamp it before use. /// \param[in] _entities Entities to be serialized. Leave empty to get /// all entities. @@ -487,7 +489,7 @@ namespace ignition /// * Entities which had a component removed /// * Entities which had a component modified /// - /// \detail The header of the message will not be populated, it is the + /// \details The header of the message will not be populated, it is the /// responsibility of the caller to timestamp it before use. public: msgs::SerializedState ChangedState() const; @@ -515,15 +517,16 @@ namespace ignition /// one will be created. /// Entities / components that are marked as removed will be removed, but /// they won't be removed if they're not present in the state. - /// \detail The header of the message will not be handled, it is the + /// \details The header of the message will not be handled, it is the /// responsibility of the caller to use the timestamp. /// \param[in] _stateMsg Message containing state to be set. public: void SetState(const msgs::SerializedState &_stateMsg); /// \brief Get a message with the serialized state of the given entities /// and components. - /// \detail The header of the message will not be populated, it is the + /// \details The header of the message will not be populated, it is the /// responsibility of the caller to timestamp it before use. + /// \param[in] _state serialized state /// \param[in] _entities Entities to be serialized. Leave empty to get /// all entities. /// \param[in] _types Type ID of components to be serialized. Leave empty @@ -549,7 +552,7 @@ namespace ignition /// * Entities which had a component modified /// /// \param[in] _state New serialized state. - /// \detail The header of the message will not be populated, it is the + /// \details The header of the message will not be populated, it is the /// responsibility of the caller to timestamp it before use. public: void ChangedState(msgs::SerializedStateMap &_state) const; @@ -558,7 +561,7 @@ namespace ignition /// one will be created. /// Entities / components that are marked as removed will be removed, but /// they won't be removed if they're not present in the state. - /// \detail The header of the message will not be handled, it is the + /// \details The header of the message will not be handled, it is the /// responsibility of the caller to use the timestamp. /// \param[in] _stateMsg Message containing state to be set. public: void SetState(const msgs::SerializedStateMap &_stateMsg); diff --git a/include/ignition/gazebo/Events.hh b/include/ignition/gazebo/Events.hh index 92c04c6e5e6..672c264c03a 100644 --- a/include/ignition/gazebo/Events.hh +++ b/include/ignition/gazebo/Events.hh @@ -55,7 +55,7 @@ namespace ignition /// \brief Event used to load plugins for an entity into simulation. /// Pass in the entity which will own the plugins, and an SDF element for - /// the entity, which may contain multiple tags. + /// the entity, which may contain multiple `` tags. using LoadPlugins = common::EventT; } diff --git a/include/ignition/gazebo/Server.hh b/include/ignition/gazebo/Server.hh index fb2e7a17ef4..f67bf6ff1c4 100644 --- a/include/ignition/gazebo/Server.hh +++ b/include/ignition/gazebo/Server.hh @@ -75,34 +75,34 @@ namespace ignition /// ## Services /// /// The following are services provided by the Server. - /// The in the service list is the name of the + /// The `` in the service list is the name of the /// simulated world. /// /// List syntax: *service_name(request_msg_type) : response_msg_type* /// - /// 1. /world//scene/info(none) : ignition::msgs::Scene + /// 1. `/world//scene/info(none)` : ignition::msgs::Scene /// + Returns the current scene information. /// - /// 2. /gazebo/resource_paths/get : ignition::msgs::StringMsg_V + /// 2. `/gazebo/resource_paths/get` : ignition::msgs::StringMsg_V /// + Get list of resource paths. /// - /// 3. /gazebo/resource_paths/add : ignition::msgs::Empty + /// 3. `/gazebo/resource_paths/add` : ignition::msgs::Empty /// + Add new resource paths. /// /// ## Topics /// /// The following are topics provided by the Server. - /// The in the service list is the name of the + /// The `` in the service list is the name of the /// simulated world. /// /// List syntax: *topic_name : published_msg_type* /// - /// 1. /world//clock : ignition::msgs::Clock + /// 1. `/world//clock` : ignition::msgs::Clock /// - /// 2. /world//stats : ignition::msgs::WorldStatistics + /// 2. `/world//stats` : ignition::msgs::WorldStatistics /// + This topic is throttled to 5Hz. /// - /// 3. /gazebo/resource_paths : ignition::msgs::StringMsg_V + /// 3. `/gazebo/resource_paths` : ignition::msgs::StringMsg_V /// + Updated list of resource paths. /// class IGNITION_GAZEBO_VISIBLE Server diff --git a/include/ignition/gazebo/ServerConfig.hh b/include/ignition/gazebo/ServerConfig.hh index dc0265d19cf..d9b94c039e5 100644 --- a/include/ignition/gazebo/ServerConfig.hh +++ b/include/ignition/gazebo/ServerConfig.hh @@ -45,7 +45,7 @@ namespace ignition class PluginInfoPrivate; /// \brief Information about a plugin that should be loaded by the /// server. - /// \detail Currently supports attaching a plugin to an entity given its + /// \details Currently supports attaching a plugin to an entity given its /// type and name, but it can't tell apart multiple entities with the same /// name in different parts of the entity tree. /// \sa const std::list &Plugins() const @@ -114,7 +114,7 @@ namespace ignition /// \brief Set the type of the entity which should receive this /// plugin. The type is used in conjuction with EntityName to /// uniquely identify an entity. - /// \param[in] _entityType Entity type string. + /// \param[in] _filename Entity type string. public: void SetFilename(const std::string &_filename); /// \brief Name of the interface within the plugin library @@ -166,7 +166,7 @@ namespace ignition /// /// Setting the SDF string will override any value set by `SetSdfFile`. /// - /// \param[in] _file Full path to an SDF file. + /// \param[in] _sdfString Full path to an SDF file. /// \return (reserved for future use) public: bool SetSdfString(const std::string &_sdfString); @@ -246,14 +246,14 @@ namespace ignition /// \brief Get whether to ignore the path specified in SDF. /// \return Whether to ignore the path specified in SDF - /// \TODO(anyone) Deprecate on Dome, SDF path will always be ignored. + /// TODO(anyone) Deprecate on Dome, SDF path will always be ignored. public: bool LogIgnoreSdfPath() const; /// \brief Set whether to ignore the path specified in SDF. Path in SDF /// should be ignored if a record path is specified on the command line, /// for example. /// \param[in] _ignore Whether to ignore the path specified in SDF - /// \TODO(anyone) Deprecate on Dome, SDF path will always be ignored. + /// TODO(anyone) Deprecate on Dome, SDF path will always be ignored. public: void SetLogIgnoreSdfPath(bool _ignore); /// \brief Add a topic to record. @@ -338,12 +338,12 @@ namespace ignition public: const std::string &RenderEngineGui() const; /// \brief Set the render engine server plugin library. - /// \param[in] _renderEngine File containing render engine library. + /// \param[in] _renderEngineServer File containing render engine library. public: void SetRenderEngineServer( const std::string &_renderEngineServer); /// \brief Set the render engine gui plugin library. - /// \param[in] _renderEngine File containing render engine library. + /// \param[in] _renderEngineGui File containing render engine library. public: void SetRenderEngineGui(const std::string &_renderEngineGui); /// \brief Instruct simulation to attach a plugin to a specific @@ -352,7 +352,7 @@ namespace ignition public: void AddPlugin(const PluginInfo &_info); /// \brief Add multiple plugins to the simulation - /// \param[in] _info List of Information about the plugin to load. + /// \param[in] _plugins List of Information about the plugin to load. public: void AddPlugins(const std::list &_plugins); /// \brief Generate PluginInfo for Log recording based on the diff --git a/include/ignition/gazebo/Util.hh b/include/ignition/gazebo/Util.hh index d3623851723..730b9511a33 100644 --- a/include/ignition/gazebo/Util.hh +++ b/include/ignition/gazebo/Util.hh @@ -210,7 +210,7 @@ namespace ignition /// `` const std::string kSdfPathEnv{"SDF_PATH"}; - /// \breif Environment variable holding server config paths. + /// \brief Environment variable holding server config paths. const std::string kServerConfigPathEnv{"IGN_GAZEBO_SERVER_CONFIG_PATH"}; /// \brief Environment variable holding paths to custom rendering engine diff --git a/include/ignition/gazebo/components/Component.hh b/include/ignition/gazebo/components/Component.hh index 727c2b48be9..bbee6d34c51 100644 --- a/include/ignition/gazebo/components/Component.hh +++ b/include/ignition/gazebo/components/Component.hh @@ -240,8 +240,10 @@ namespace components /// override this function to support serialization. /// /// \param[in] _out Out stream. - public: virtual void Serialize(std::ostream &/*_out*/) const + public: virtual void Serialize(std::ostream &_out) const { + // This will avoid a doxygen warning + (void)_out; static bool warned{false}; if (!warned) { @@ -257,8 +259,10 @@ namespace components /// override this function to support deserialization. /// /// \param[in] _in In stream. - public: virtual void Deserialize(std::istream &/*_in*/) + public: virtual void Deserialize(std::istream &_in) { + // This will avoid a doxygen warning + (void)_in; static bool warned{false}; if (!warned) { @@ -358,7 +362,6 @@ namespace components /// \param[in] _data New data for this component. /// \param[in] _eql Equality comparison function. This function should /// return true if two instances of DataType are equal. - /// \param[in} _ecm Pointer to the entity component manager. /// \return True if the _eql function returns false. public: bool SetData(const DataType &_data, const std::function< @@ -396,14 +399,14 @@ namespace components /// \param[in] _component Component to compare to /// \return True. public: bool operator==(const Component &) const; + Serializer> &_component) const; /// \brief Components with no data are always equal to another instance of /// the same type. /// \param[in] _component Component to compare to /// \return False. public: bool operator!=(const Component &) const; + Serializer> &_component) const; // Documentation inherited public: ComponentTypeId TypeId() const override; diff --git a/include/ignition/gazebo/components/ContactSensor.hh b/include/ignition/gazebo/components/ContactSensor.hh index 4df9ef12a62..f7721015799 100644 --- a/include/ignition/gazebo/components/ContactSensor.hh +++ b/include/ignition/gazebo/components/ContactSensor.hh @@ -31,7 +31,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace components { /// \brief TODO(anyone) Substitute with sdf::Contact once that exists? - /// This is currently the whole element. + /// This is currently the whole `` element. using ContactSensor = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ContactSensor", ContactSensor) diff --git a/include/ignition/gazebo/components/Factory.hh b/include/ignition/gazebo/components/Factory.hh index 490d18e813d..01ef49694d1 100644 --- a/include/ignition/gazebo/components/Factory.hh +++ b/include/ignition/gazebo/components/Factory.hh @@ -171,9 +171,9 @@ namespace components /// \brief Unregister a component so that the factory can't create instances /// of the component or its storage anymore. - /// \detail This function will not reset the `typeId` static variable within - /// the component type itself. Prefer using the templated `Unregister` - /// function when possible. + /// \details This function will not reset the `typeId` static variable + /// within the component type itself. Prefer using the templated + /// `Unregister` function when possible. /// \param[in] _typeId Type of component to unregister. public: void Unregister(ComponentTypeId _typeId) { @@ -310,12 +310,12 @@ namespace components private: std::map storagesById; /// \brief A list of IDs and their equivalent names. - /// \detail Make it non-static on version 2.0. + /// \details Make it non-static on version 2.0. public: inline static std::map namesById; /// \brief Keep track of the runtime names for types and warn the user if /// they try to register different types with the same typeName. - /// \detail Make it non-static on version 2.0. + /// \details Make it non-static on version 2.0. public: inline static std::map runtimeNamesById; }; @@ -324,7 +324,7 @@ namespace components /// /// Use this macro to register components. /// - /// \detail Each time a plugin which uses a component is loaded, it tries to + /// \details Each time a plugin which uses a component is loaded, it tries to /// register the component again, so we prevent that. /// \param[in] _compType Component type name. /// \param[in] _classname Class name for component. diff --git a/include/ignition/gazebo/components/LogicalCamera.hh b/include/ignition/gazebo/components/LogicalCamera.hh index 8c1daab9811..7ed64631635 100644 --- a/include/ignition/gazebo/components/LogicalCamera.hh +++ b/include/ignition/gazebo/components/LogicalCamera.hh @@ -31,7 +31,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace components { /// \brief TODO(anyone) Substitute with sdf::LogicalCamera once that exists? - /// This is currently the whole element. + /// This is currently the whole `` element. using LogicalCamera = Component; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalCamera", LogicalCamera) diff --git a/include/ignition/gazebo/components/Serialization.hh b/include/ignition/gazebo/components/Serialization.hh index 5fe9999dcee..7fd3ee7765e 100644 --- a/include/ignition/gazebo/components/Serialization.hh +++ b/include/ignition/gazebo/components/Serialization.hh @@ -148,7 +148,7 @@ namespace serializers /// \brief Deserialization /// \param[in] _in Input stream. - /// \param[in] _vec Message to populate + /// \param[in] _msg Message to populate /// \return The stream. public: static std::istream &Deserialize(std::istream &_in, google::protobuf::Message &_msg) diff --git a/include/ignition/gazebo/gui/GuiSystem.hh b/include/ignition/gazebo/gui/GuiSystem.hh index c0311010427..1de32584eb8 100644 --- a/include/ignition/gazebo/gui/GuiSystem.hh +++ b/include/ignition/gazebo/gui/GuiSystem.hh @@ -51,8 +51,13 @@ namespace gazebo /// \param[in] _info Current simulation information, such as time. /// \param[in] _ecm Mutable reference to the ECM, so the system can read /// and write entities and their components. - public: virtual void Update(const UpdateInfo &/*_info*/, - EntityComponentManager &/*_ecm*/){} + public: virtual void Update(const UpdateInfo &_info, + EntityComponentManager &_ecm) + { + // This will avoid many doxygen warnings + (void)_info; + (void)_ecm; + } }; } } diff --git a/include/ignition/gazebo/rendering/RenderUtil.hh b/include/ignition/gazebo/rendering/RenderUtil.hh index 6e8e82f98e7..90912f44316 100644 --- a/include/ignition/gazebo/rendering/RenderUtil.hh +++ b/include/ignition/gazebo/rendering/RenderUtil.hh @@ -129,7 +129,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Set the entity being selected /// \param[in] _node Node representing the selected entity - /// \TODO(anyone) Make const ref when merging forward + /// TODO(anyone) Make const ref when merging forward // NOLINTNEXTLINE public: void SetSelectedEntity(rendering::NodePtr _node); @@ -142,7 +142,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Get the entity being selected. This will only return the /// last entity selected. - /// \TODO(anyone) Deprecate in favour of SelectedEntities + /// TODO(anyone) Deprecate in favour of SelectedEntities public: rendering::NodePtr SelectedEntity() const; /// \brief Get the entities currently selected, in order of selection. diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 162a307b96a..ca2261a4812 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -111,7 +111,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Create an actor /// \param[in] _id Unique actor id - /// \param[in] _visual Actor sdf dom + /// \param[in] _actor Actor sdf dom /// \param[in] _parentId Parent id /// \return Actor object created from the sdf dom public: rendering::VisualPtr CreateActor(Entity _id, @@ -130,7 +130,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// the correct parent. /// \param[in] _gazeboId Entity in Gazebo /// \param[in] _sensorName Name of sensor node in Ignition Rendering. - /// \param[in] _parentId Parent Id on Gazebo. + /// \param[in] _parentGazeboId Parent Id on Gazebo. /// \return True if sensor is successfully handled public: bool AddSensor(Entity _gazeboId, const std::string &_sensorName, Entity _parentGazeboId = 0); @@ -188,7 +188,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// Usually, this will be a model or a light. /// \param[in] _visual Child visual /// \return Top level visual containining this visual - /// \TODO(anyone) Make it const ref when merging forward + /// TODO(anyone) Make it const ref when merging forward public: rendering::VisualPtr TopLevelVisual( // NOLINTNEXTLINE rendering::VisualPtr _visual) const; diff --git a/src/gui/plugins/align_tool/AlignTool.hh b/src/gui/plugins/align_tool/AlignTool.hh index 41a0d4d726d..f72a8ff5a8f 100644 --- a/src/gui/plugins/align_tool/AlignTool.hh +++ b/src/gui/plugins/align_tool/AlignTool.hh @@ -123,7 +123,7 @@ namespace gazebo /// \brief Returns the top level node of the passed in node within /// a given scene /// \param[in] _scene The scene to check - /// \param[in] _visual The node to get the top level node for + /// \param[in] _node The node to get the top level node for public: rendering::NodePtr TopLevelNode(rendering::ScenePtr &_scene, rendering::NodePtr &_node) const; diff --git a/src/gui/plugins/modules/EntityContextMenu.hh b/src/gui/plugins/modules/EntityContextMenu.hh index 0dd8f567b6b..80de7970282 100644 --- a/src/gui/plugins/modules/EntityContextMenu.hh +++ b/src/gui/plugins/modules/EntityContextMenu.hh @@ -54,7 +54,6 @@ namespace gazebo public: ~EntityContextMenu() override; /// \brief Callback when a context menu item is invoked - /// \param[in] _request Request type /// \param[in] _data Request data /// \param[in] _type Entity type public: Q_INVOKABLE void OnRemove( diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.hh b/src/gui/plugins/resource_spawner/ResourceSpawner.hh index d95e5727cb0..377ad95ec56 100644 --- a/src/gui/plugins/resource_spawner/ResourceSpawner.hh +++ b/src/gui/plugins/resource_spawner/ResourceSpawner.hh @@ -212,6 +212,8 @@ namespace gazebo /// \brief Callback when a request is made to download a fuel resource. /// \param[in] _path URI to the fuel resource + /// \param[in] _name Name of the resource + /// \param[in] _owner The name of the owner /// \param[in] index The index of the grid pane to update public slots: void OnDownloadFuelResource(const QString &_path, const QString &_name, const QString &_owner, int index); @@ -231,7 +233,7 @@ namespace gazebo /// sets the model's thumbnail path attribute to it, no action is /// taken if no thumbnail is found. /// \param[in] _thumbnailPath The path to search for a thumbnail - /// \param[in] _model The model to update with the thumbnail information + /// \param[in] _resource The model to update with the thumbnail information public: void SetThumbnail(const std::string &_thumbnailPath, Resource &_resource); diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh index 89a5dbef26d..1f743a43236 100644 --- a/src/gui/plugins/scene3d/Scene3D.hh +++ b/src/gui/plugins/scene3d/Scene3D.hh @@ -243,11 +243,11 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { const std::string &_savePath); /// \brief Set whether to record video using sim time as timestamp - /// \param[in] _true True record video using sim time + /// \param[in] _useSimTime True record video using sim time public: void SetRecordVideoUseSimTime(bool _useSimTime); /// \brief Set whether to record video in lockstep mode - /// \param[in] _true True to record video in lockstep mode + /// \param[in] _lockstep True to record video in lockstep mode public: void SetRecordVideoLockstep(bool _lockstep); /// \brief Set video recorder bitrate in bps @@ -286,7 +286,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief True to set the camera to follow the target in world frame, /// false to follow in target's local frame - /// \param[in] _gain Camera follow p gain. + /// \param[in] _worldFrame True to use the world frame. public: void SetFollowWorldFrame(bool _worldFrame); /// \brief Set the camera follow offset position @@ -426,7 +426,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief Retrieve the point on a plane at z = 0 in the 3D scene hit by a /// ray cast from the given 2D screen coordinates. - /// \param[in] _screenPod 2D coordinates on the screen, in pixels. + /// \param[in] _screenPos 2D coordinates on the screen, in pixels. /// \return 3D coordinates of a point in the 3D scene. public: math::Vector3d ScreenToPlane(const math::Vector2i &_screenPos) const; @@ -582,11 +582,11 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { const std::string &_savePath); /// \brief Set whether to record video using sim time as timestamp - /// \param[in] _true True record video using sim time + /// \param[in] _useSimTime True record video using sim time public: void SetRecordVideoUseSimTime(bool _useSimTime); /// \brief Set whether to record video in lockstep mode - /// \param[in] _true True to record video in lockstep mode + /// \param[in] _lockstep True to record video in lockstep mode public: void SetRecordVideoLockstep(bool _lockstep); /// \brief Set video recorder bitrate in bps @@ -625,7 +625,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { /// \brief True to set the camera to follow the target in world frame, /// false to follow in target's local frame - /// \param[in] _gain Camera follow p gain. + /// \param[in] _worldFrame True to use the world frame. public: void SetFollowWorldFrame(bool _worldFrame); /// \brief Set the camera follow offset position diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh index 9e0f243e376..75149eef0fc 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.hh +++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh @@ -40,23 +40,23 @@ namespace systems /// \brief A plugin for simulating battery usage /// /// This system processes the following sdf parameters: - /// name of the battery (required) - /// Initial voltage of the battery (required) - /// Voltage at full charge - /// Amount of voltage decrease when no + /// - `` name of the battery (required) + /// - `` Initial voltage of the battery (required) + /// - `` Voltage at full charge + /// - `` Amount of voltage decrease when no /// charge - /// Initial charge of the battery (Ah) - /// Total charge that the battery can hold (Ah) - /// Internal resistance (Ohm) - /// coefficient for smoothing current [0, 1]. - /// power load on battery (required) (Watts) - /// If true, the battery can be recharged - /// If true, the start/stop signals for recharging the + /// - `` Initial charge of the battery (Ah) + /// - `` Total charge that the battery can hold (Ah) + /// - `` Internal resistance (Ohm) + /// - `` coefficient for smoothing current [0, 1]. + /// - `` power load on battery (required) (Watts) + /// - `` If true, the battery can be recharged + /// - `` If true, the start/stop signals for recharging the /// battery will also be available via topics. The /// regular Ignition services will still be available. - /// Hours taken to fully charge the battery. - /// (Required if is set to true) - /// True to change the battery behavior to fix some issues + /// - `` Hours taken to fully charge the battery. + /// (Required if `` is set to true) + /// - `` True to change the battery behavior to fix some issues /// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225. class LinearBatteryPlugin : public System, diff --git a/src/systems/breadcrumbs/Breadcrumbs.hh b/src/systems/breadcrumbs/Breadcrumbs.hh index e57be624022..a0bd9022d6d 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.hh +++ b/src/systems/breadcrumbs/Breadcrumbs.hh @@ -46,39 +46,40 @@ namespace systems /// get deployed/spawned at the location of the model to which this system is /// attached. Each breadcrumb is a complete sdf::Model. When deployed, the /// pose of the breadcrumb model is offset from the containing model by the - /// pose specified in the element of the breadcrumb model. A name is + /// pose specified in the `` element of the breadcrumb model. A name is /// generated for the breadcrumb by appending the current count of deployments - /// to the name specified in the breadcrumb element. The model - /// specified in the parameter serves as a template for deploying - /// multiple breadcrumbs of the same type. Including models from Fuel is - /// accomplished by creating a that includes the Fuel model using the - /// tag. See the example in examples/worlds/breadcrumbs.sdf. + /// to the name specified in the breadcrumb `` element. The model + /// specified in the `` parameter serves as a template for + /// deploying multiple breadcrumbs of the same type. Including models from + /// Fuel is accomplished by creating a `` that includes the Fuel + /// model using the `` tag. + /// See the example in examples/worlds/breadcrumbs.sdf. /// /// System Paramters /// - /// ``: Custom topic to be used to deploy breadcrumbs. If topic is not - /// set, the default topic with the following pattern would be used - /// "/model//breadcrumbs//deploy". The topic type - /// is ignition.msgs.Empty - /// ``: The maximum number of times this breadcrumb can be - /// deployed. Once this many are deployed, publishing on the deploy topic will - /// have no effect. If a negative number is set, the maximum deployment will - /// be unbounded. If a value of zero is used, then the breadcrumb system will - /// be disabled. A zero value is useful for situations where SDF files are - /// programmatically created. The remaining deployment count is available on - /// the `/remaining` topic. - /// ``: The time in which the breadcrumb entity's + /// - ``: Custom topic to be used to deploy breadcrumbs. If topic is + /// not set, the default topic with the following pattern would be used + /// `/model//breadcrumbs//deploy`. The topic + /// type is ignition.msgs.Empty + /// - ``: The maximum number of times this breadcrumb can be + /// deployed. Once this many are deployed, publishing on the deploy topic + /// will have no effect. If a negative number is set, the maximum deployment + /// will be unbounded. If a value of zero is used, then the breadcrumb system + /// will be disabled. A zero value is useful for situations where SDF files + /// are programmatically created. The remaining deployment count is available + /// on the `/remaining` topic. + /// - ``: The time in which the breadcrumb entity's /// dynamics remain enabled. After his specified time, the breadcrumb will /// be made static. If this value is <= 0 or the param is not specified, the /// breadcrumb model's dynamics will not be modified. - /// ``: Geometry that represents the bounding volume of + /// - ``: Geometry that represents the bounding volume of /// the performer. Only `` is supported currently. When this /// parameter is present, the deployed models will be performers. - /// ``: If true, the deployed model will be renamed if another - /// model with the same name already exists in the world. If false and there - /// is another model with the same name, the breadcrumb will not be deployed. - /// Defaults to false. - /// ``: This is the model used as a template for deploying + /// - ``: If true, the deployed model will be renamed if + /// another model with the same name already exists in the world. If false + /// and there is another model with the same name, the breadcrumb will not + /// be deployed. Defaults to false. + /// - ``: This is the model used as a template for deploying /// breadcrumbs. class Breadcrumbs : public System, @@ -171,4 +172,3 @@ namespace systems } #endif - diff --git a/src/systems/buoyancy/Buoyancy.hh b/src/systems/buoyancy/Buoyancy.hh index 7d9f1a4ae5d..55d040cdb8e 100644 --- a/src/systems/buoyancy/Buoyancy.hh +++ b/src/systems/buoyancy/Buoyancy.hh @@ -45,7 +45,7 @@ namespace systems /// /// ## System Parameters /// - /// * sets the density of the fluid that surrounds + /// * `` sets the density of the fluid that surrounds /// the buoyant object. /// /// ## Example diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh index a7204e5a80d..90c4dfdb06f 100644 --- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh +++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh @@ -36,10 +36,10 @@ namespace systems **/ /// \brief Record video from a camera sensor /// The system takes in the following parameter: - /// Name of topic for the video recorder service. If this is - /// not specified, the topic defaults to: - /// /world//link// - /// sensor//record_video + /// - `` Name of topic for the video recorder service. If this is + /// not specified, the topic defaults to:
+ /// `/world//link//` + /// `sensor//record_video` class CameraVideoRecorder: public System, public ISystemConfigure, @@ -69,4 +69,3 @@ namespace systems } } #endif - diff --git a/src/systems/detachable_joint/DetachableJoint.hh b/src/systems/detachable_joint/DetachableJoint.hh index 5a1089321ab..f52dc9d24a9 100644 --- a/src/systems/detachable_joint/DetachableJoint.hh +++ b/src/systems/detachable_joint/DetachableJoint.hh @@ -40,17 +40,17 @@ namespace systems /// /// Parameters: /// - /// : Name of the link in the parent model to be used in + /// - ``: Name of the link in the parent model to be used in /// creating a fixed joint with a link in the child model. /// - /// : Name of the model to which this model will be connected + /// - ``: Name of the model to which this model will be connected /// - /// : Name of the link in the child model to be used in + /// - ``: Name of the link in the child model to be used in /// creating a fixed joint with a link in the parent model. /// - /// (optional): Topic name to be used for detaching connections + /// - `` (optional): Topic name to be used for detaching connections /// - /// (optional): If true, the system + /// - `` (optional): If true, the system /// will not print a warning message if a child model does not exist yet. /// Otherwise, a warning message is printed. Defaults to false. diff --git a/src/systems/log_video_recorder/LogVideoRecorder.hh b/src/systems/log_video_recorder/LogVideoRecorder.hh index 7c2a87fc5e8..29d61208d76 100644 --- a/src/systems/log_video_recorder/LogVideoRecorder.hh +++ b/src/systems/log_video_recorder/LogVideoRecorder.hh @@ -39,13 +39,14 @@ namespace systems /// There are two ways to specify what entities in the log playback to follow /// and record videos for: 1) by entity name and 2) by region. See the /// following parameters: - /// Name of entity to record. - /// Axis-aligned box where entities are at start of log - /// Min corner position of box region. - /// Max corner position of box region. - /// Sim time when recording should start - /// Sim time when recording should end - /// Exit ign-gazebo when log playback recording ends + /// - `` Name of entity to record. + /// - `` Axis-aligned box where entities are at start of log + /// + `` Min corner position of box region. + /// + `` Max corner position of box region. + /// - `` Sim time when recording should start + /// - `` Sim time when recording should end + /// - `` Exit ign-gazebo when log playback recording ends + /// /// When recording is finished. An `end` string will be published to the /// `/log_video_recorder/status` topic and the videos are saved to a /// timestamped directory @@ -78,4 +79,3 @@ namespace systems } } #endif - diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh index 6ec0c390ab4..3dcaeb67a22 100644 --- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh +++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh @@ -34,7 +34,7 @@ namespace systems /// \brief A plugin for logical audio detection. /// - /// Each tag can accept multiple sensors (sound sources + /// Each `` tag can accept multiple sensors (sound sources /// and/or microphones). /// After each simulation step, microphones check if audio /// was detected by any sources in the world. @@ -44,90 +44,92 @@ namespace systems /// /// Secifying an audio source via SDF is done as follows: /// - /// A new audio source in the environment, which has the + /// - `` A new audio source in the environment, which has the /// following child elements: - /// * The source ID, which must be unique and an integer >= 0. + /// + `` The source ID, which must be unique and an integer >= 0. /// An ID < 0 results in undefined behavior. /// The ID must be unique within the scope of all other source IDs /// in the plugin's parent element - so, if a source was created in a - /// with an ID of 1, no other sources in the same model can have - /// an ID of 1 (however, sources that belong to other models can have an - /// ID of 1). - /// * The pose, expressed as "x y z roll pitch yaw". + /// `` with an ID of 1, no other sources in the same model can + /// have an ID of 1 (however, sources that belong to other models can + /// have an ID of 1). + /// + `` The pose, expressed as "x y z roll pitch yaw". /// Each pose coordinate must be separated by whitespace. /// The pose is defined relative to the plugin's parent element. - /// So, if the plugin is used inside of a tag, then the - /// source's is relative to the model's pose. - /// If the plugin is used inside of a tag, then the source's - /// is relative to the world (i.e., specifies an + /// So, if the plugin is used inside of a `` tag, then the + /// source's `` is relative to the model's pose. + /// If the plugin is used inside of a `` tag, then the source's + /// `` is relative to the world (i.e., `` specifies an /// absolute pose). /// If no pose is specified, {0, 0, 0, 0, 0, 0} will be used. - /// * The attenuation function. + /// + `` The attenuation function. /// See logical_audio::AttenuationFunction for a list of valid /// attenuation functions, and logical_audio::SetAttenuationFunction /// for how to specify an attenuation function in SDF. - /// * The attenuation shape. + /// + `` The attenuation shape. /// See logical_audio::AttenuationShape for a list of valid /// attenuation shapes, and logical_audio::SetAttenuationShape for how /// to specify an attenuation shape in SDF. - /// * The inner radius of the attenuation shape. + /// + `` The inner radius of the attenuation shape. /// This value must be >= 0.0. The volume of the source will be - /// at locations that have a distance <= inner + /// `` at locations that have a distance <= inner /// radius from the source. - /// * The falloff distance. This value must be greater - /// than the value of the source's . This defines the - /// distance from the audio source where the volume becomes 0. - /// * The volume level emitted from the source. This must + /// + `` The falloff distance. This value must be + /// greater than the value of the source's ``. This + /// defines the distance from the audio source where the volume + /// becomes 0. + /// + `` The volume level emitted from the source. This must /// be a value between 0.0 and 1.0 (representing 0% to 100%). - /// * Whether the source should play immediately or not. + /// + `` Whether the source should play immediately or not. /// Use true to initiate audio immediately, and false otherwise. - /// * The duration (in seconds) audio is played from the + /// + `` The duration (in seconds) audio is played from the /// source. This value must be an integer >= 0. /// A value of 0 means that the source will play for an infinite amount /// of time. /// /// Specifying a microphone via SDF is done as follows: /// - /// A new microphone in the environment, + /// - `` A new microphone in the environment, /// which has the following child elements: - /// * The microphone ID, which must be unique and an integer >= 0. + /// + `` The microphone ID, which must be unique and an integer >= 0. /// An ID < 0 results in undefined behavior. /// The ID must be unique within the scope of all other microphone IDs /// in the plugin's parent element - so, if a microphone was created in - /// a with an ID of 1, no other microphones in the same model + /// a `` with an ID of 1, no other microphones in the same model /// can have an ID of 1 (however, microphones that belong to other /// models can have an ID of 1). - /// * The pose, expressed as "x y z roll pitch yaw". + /// + `` The pose, expressed as "x y z roll pitch yaw". /// Each pose coordinate must be separated by whitespace. /// The pose is defined relative to the plugin's parent element. - /// So, if the plugin is used inside of a tag, then the - /// source's is relative to the model's pose. - /// If the plugin is used inside of a tag, then the source's - /// is relative to the world (i.e., specifies an + /// So, if the plugin is used inside of a `` tag, then the + /// source's ``is relative to the model's pose. + /// If the plugin is used inside of a `` tag, then the source's + /// `` is relative to the world (i.e., `` specifies an /// absolute pose). /// If no pose is specified, {0, 0, 0, 0, 0, 0} will be used. - /// * The minimum volume level the microphone + /// + `` The minimum volume level the microphone /// can detect. This must be a value between 0.0 and 1.0 /// (representing 0% to 100%). /// If no volume threshold is specified, 0.0 will be used. /// /// Sources can be started and stopped via Ignition service calls. /// If a source is successfully created, the following services will be - /// created for the source ( is the scoped name for the source - see - /// ignition::gazebo::scopedName for more details - and is the value - /// specified in the source's tag from the SDF): - /// * /source_/play + /// created for the source (`` is the scoped name for the source - see + /// ignition::gazebo::scopedName for more details - and `` is the value + /// specified in the source's `` tag from the SDF): + /// * `/source_/play` /// * Starts playing the source with the specified ID. /// If the source is already playing, nothing happens. - /// * /source_/stop + /// * `/source_/stop` /// * Stops playing the source with the specified ID. /// If the source is already stopped, nothing happens. /// /// Microphone detection information can be retrieved via Ignition topics. /// Whenever a microphone detects a source, it publishes a message to the - /// /mic_/detection topic, where is the scoped name + /// `/mic_/detection` topic, where `` is the scoped name /// for the microphone - see ignition::gazebo::scopedName for more details - - /// and is the value specified in the microphone's tag from the SDF. + /// and `` is the value specified in the microphone's `` tag from the + /// SDF. class LogicalAudioSensorPlugin : public System, public ISystemConfigure, diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.hh b/src/systems/multicopter_control/MulticopterVelocityControl.hh index 72b73015f19..0fe9d7ece67 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -126,11 +126,11 @@ namespace systems /// value of 0 implies noise is NOT applied to the component. The default /// value is (0, 0, 0). /// - /// rotorConfiguration: This contains a list of elements for each + /// rotorConfiguration: This contains a list of `` elements for each /// rotor in the vehicle. This is a required parameter. /// /// rotor: Contains information about a rotor in the vehicle. All the - /// elements of are required parameters. + /// elements of `` are required parameters. /// /// jointName: The name of the joint associated with this rotor. /// diff --git a/src/systems/performer_detector/PerformerDetector.hh b/src/systems/performer_detector/PerformerDetector.hh index ebb0bb8f4cb..151ad9727ed 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -53,8 +53,8 @@ namespace systems /// a value set to "1" if the performer is entering the detector's region and /// "0" if the performer is leaving the region. /// - /// The PerformerDetector has to be attached to a and it's region is - /// centered on the containing model's origin. + /// The PerformerDetector has to be attached to a `` and it's region + /// is centered on the containing model's origin. /// /// The system does not assume that levels are enabled, but it does require /// performers to be specified. diff --git a/src/systems/physics/EntityFeatureMap.hh b/src/systems/physics/EntityFeatureMap.hh index f9d8fe52c02..e38375169e2 100644 --- a/src/systems/physics/EntityFeatureMap.hh +++ b/src/systems/physics/EntityFeatureMap.hh @@ -141,7 +141,7 @@ namespace systems::physics_system /// to an entity with a different set of features. This overload takes a /// physics entity as input /// \tparam ToFeatureList The list of features of the resulting entity. - /// \param[in] _entity Physics entity with required features. + /// \param[in] _physicsEntity Physics entity with required features. /// \return Physics entity with features in ToFeatureList. nullptr if the /// entity can't be found or the physics engine doesn't support the /// requested feature. @@ -234,7 +234,7 @@ namespace systems::physics_system } /// \brief Remove physics entity from all associated maps - /// \param[in] _entity Gazebo entity. + /// \param[in] _physicsEntity Physics entity. /// \return True if the entity was found and removed. public: bool Remove(const RequiredEntityPtr &_physicsEntity) { diff --git a/src/systems/touch_plugin/TouchPlugin.hh b/src/systems/touch_plugin/TouchPlugin.hh index b74097d751d..251fc2e8bfa 100644 --- a/src/systems/touch_plugin/TouchPlugin.hh +++ b/src/systems/touch_plugin/TouchPlugin.hh @@ -42,21 +42,22 @@ namespace systems /// /// Parameters: /// - /// Scoped name of the desired collision entity that is checked to - /// see if it's touching this model. This can be a substring of the - /// desired collision name so we match more than one collision. For - /// example, using the name of a model will match all its collisions. + /// - `` Scoped name of the desired collision entity that is checked + /// to see if it's touching this model. This can be a substring + /// of the desired collision name so we match more than one + /// collision. For example, using the name of a model will match + /// all its collisions. /// - ///
diff --git a/examples/worlds/sensors.sdf b/examples/worlds/sensors.sdf index 48af629339d..eefd6a8ee8c 100644 --- a/examples/worlds/sensors.sdf +++ b/examples/worlds/sensors.sdf @@ -116,6 +116,7 @@ 30 true altimeter + true @@ -136,6 +137,7 @@ 30 true air_pressure + true 123 @@ -152,12 +154,14 @@ 100 true imu + true
1 100 true magnetometer + true diff --git a/examples/worlds/sensors_demo.sdf b/examples/worlds/sensors_demo.sdf index 71a2e973bc0..ffc2c2dd19b 100644 --- a/examples/worlds/sensors_demo.sdf +++ b/examples/worlds/sensors_demo.sdf @@ -257,10 +257,12 @@ 30 true camera_alone + true 10 depth_camera + true 1.05 @@ -325,6 +327,7 @@ " lidar 10 + true @@ -396,6 +399,7 @@ 30 true rgbd_camera + true From 7b326dcbf1b76576cd543cb59621c130b989bd27 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 31 Aug 2021 10:26:42 -0700 Subject: [PATCH 12/17] Remove extra xml version line in pendulum_links example world (#1002) Signed-off-by: Ian Chen --- examples/worlds/pendulum_links.sdf | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/worlds/pendulum_links.sdf b/examples/worlds/pendulum_links.sdf index 2f62bab25c3..1927835b7a4 100644 --- a/examples/worlds/pendulum_links.sdf +++ b/examples/worlds/pendulum_links.sdf @@ -9,7 +9,6 @@ --> - From f5a457dcc536fe3f24e44a68cc63e8c8b30af812 Mon Sep 17 00:00:00 2001 From: Tim Player Date: Fri, 3 Sep 2021 16:16:34 -0700 Subject: [PATCH 13/17] Update DART deps to local (#1005) Signed-off-by: Tim Player --- docker/scripts/install_ign_deps.sh | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/docker/scripts/install_ign_deps.sh b/docker/scripts/install_ign_deps.sh index 18d9ab52f7e..63948f5fb68 100755 --- a/docker/scripts/install_ign_deps.sh +++ b/docker/scripts/install_ign_deps.sh @@ -67,10 +67,11 @@ sudo apt-get install --no-install-recommends -y \ # ign-physics dependencies sudo apt-get install --no-install-recommends -y \ libeigen3-dev \ - dart6-data \ - libdart6-collision-ode-dev \ - libdart6-dev \ - libdart6-utils-urdf-dev \ + libdart-collision-ode-dev \ + libdart-dev \ + libdart-external-ikfast-dev \ + libdart-external-odelcpsolver-dev \ + libdart-utils-urdf-dev \ libbenchmark-dev # ign-gazebo dependencies From 1e6a9d1cbcc2a8d39ac01df32c88e68887d0d627 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 3 Sep 2021 16:19:52 -0700 Subject: [PATCH 14/17] Fix selection buffer crash on resize (#969) Signed-off-by: Ian Chen --- src/gui/plugins/scene3d/Scene3D.cc | 1 + 1 file changed, 1 insertion(+) diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 1053b310370..95fb924e46e 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -442,6 +442,7 @@ void IgnRenderer::Render() { IGN_PROFILE("IgnRenderer::Render Pre-render camera"); this->dataPtr->camera->PreRender(); + this->dataPtr->camera->Render(); } this->textureDirty = false; } From 5858ae64bf0061d806d406d137577dec10eb403a Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Wed, 8 Sep 2021 08:49:48 -0700 Subject: [PATCH 15/17] Workaround for setting visual cast shadows without material (#1015) Signed-off-by: Ian Chen --- src/rendering/SceneManager.cc | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 7932c56aeef..e791ab8223c 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -315,7 +315,14 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id, double productAlpha = (1.0-_visual.Transparency()) * (1.0 - submeshMat->Transparency()); submeshMat->SetTransparency(1 - productAlpha); + + // unlike setting transparency above, the parent submesh are not + // notified about the the cast shadows changes. So we need to set + // the material back to the submesh. + // \todo(anyone) find way to propate cast shadows changes tos submesh + // in ign-rendering submeshMat->SetCastShadows(_visual.CastShadows()); + submesh->SetMaterial(submeshMat); } } } From a04b4c7dce832eae22d3cdea5eb9d1c136c05101 Mon Sep 17 00:00:00 2001 From: Jenn Nguyen Date: Wed, 8 Sep 2021 11:57:41 -0700 Subject: [PATCH 16/17] Fixed GUI's ComponentInspector light parameter (#1018) Signed-off-by: Jenn Nguyen --- src/gui/plugins/component_inspector/ComponentInspector.cc | 6 ------ 1 file changed, 6 deletions(-) diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index 82b2f1528a7..6506f23e10b 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -458,12 +458,6 @@ void ComponentInspector::Update(const UpdateInfo &, continue; } - if (typeId == components::Light::typeId) - { - this->SetType("light"); - continue; - } - if (typeId == components::Actor::typeId) { this->SetType("actor"); From 59ff8532d0699f18cf9d0e34aa1bc0afecb73671 Mon Sep 17 00:00:00 2001 From: ddengster Date: Fri, 10 Sep 2021 06:09:08 +0800 Subject: [PATCH 17/17] Collada world exporter now exporting lights (#912) Signed-off-by: ddengster Signed-off-by: Louise Poubel Co-authored-by: Louise Poubel --- CMakeLists.txt | 2 +- .../ColladaWorldExporter.cc | 52 ++++- test/integration/collada_world_exporter.cc | 21 +++ test/worlds/collada_world_exporter_lights.sdf | 177 ++++++++++++++++++ 4 files changed, 249 insertions(+), 3 deletions(-) create mode 100644 test/worlds/collada_world_exporter_lights.sdf diff --git a/CMakeLists.txt b/CMakeLists.txt index 26fe0d3b11d..a0b0d3df539 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -65,7 +65,7 @@ set(IGN_MSGS_VER ${ignition-msgs7_VERSION_MAJOR}) #-------------------------------------- # Find ignition-common # Always use the profiler component to get the headers, regardless of status. -ign_find_package(ignition-common4 +ign_find_package(ignition-common4 VERSION 4.2 COMPONENTS profiler events diff --git a/src/systems/collada_world_exporter/ColladaWorldExporter.cc b/src/systems/collada_world_exporter/ColladaWorldExporter.cc index 454d3b56eac..66ee000dfad 100644 --- a/src/systems/collada_world_exporter/ColladaWorldExporter.cc +++ b/src/systems/collada_world_exporter/ColladaWorldExporter.cc @@ -21,6 +21,7 @@ #include #include +#include #include #include #include @@ -33,9 +34,10 @@ #include #include -#include +#include #include #include +#include #include #include @@ -244,9 +246,55 @@ class ignition::gazebo::systems::ColladaWorldExporterPrivate return true; }); + std::vector lights; + _ecm.Each( + [&](const Entity &/*_entity*/, + const components::Light *_light, + const components::Name *_name)->bool + { + std::string name = _name->Data(); + const auto& sdfLight = _light->Data(); + + common::ColladaLight p; + p.name = name; + if (sdfLight.Type() == sdf::LightType::POINT) + { + p.type = "point"; + } + else if (sdfLight.Type() == sdf::LightType::SPOT) + { + p.type = "spot"; + } + else if (sdfLight.Type() == sdf::LightType::DIRECTIONAL) + { + p.type = "directional"; + } + else + { + p.type = "invalid"; + } + + p.position = sdfLight.RawPose().Pos(); + p.direction = sdfLight.RawPose().Rot().RotateVector(sdfLight.Direction()); + p.diffuse = sdfLight.Diffuse(); + + p.constantAttenuation = sdfLight.ConstantAttenuationFactor(); + p.linearAttenuation = sdfLight.LinearAttenuationFactor(); + p.quadraticAttenuation = sdfLight.QuadraticAttenuationFactor(); + + // Falloff angle is treated as the outer angle in blender + // https://community.khronos.org/t/spotlight-properties/7111/7 + p.falloffAngleDeg = sdfLight.SpotOuterAngle().Degree(); + p.falloffExponent = sdfLight.SpotFalloff(); + + lights.push_back(p); + return true; + }); + common::ColladaExporter exporter; exporter.Export(&worldMesh, "./" + worldMesh.Name(), true, - subMeshMatrix); + subMeshMatrix, lights); ignmsg << "The world has been exported into the " << "./" + worldMesh.Name() << " directory." << std::endl; this->exported = true; diff --git a/test/integration/collada_world_exporter.cc b/test/integration/collada_world_exporter.cc index a2f4d036e8e..46524b5a88e 100644 --- a/test/integration/collada_world_exporter.cc +++ b/test/integration/collada_world_exporter.cc @@ -146,6 +146,27 @@ TEST_F(ColladaWorldExporterFixture, ExportWorldMadeFromObj) common::removeAll(outputPath); } +TEST_F(ColladaWorldExporterFixture, ExportWorldWithLights) +{ + this->LoadWorld(common::joinPaths("test", "worlds", + "collada_world_exporter_lights.sdf")); + + // Cleanup + common::removeAll("./collada_world_exporter_lights_test"); + + // The export directory shouldn't exist. + EXPECT_FALSE(common::exists("./collada_world_exporter_lights_test")); + + // Run one iteration which should export the world. + server->Run(true, 1, false); + + // The export directory should now exist. + EXPECT_TRUE(common::exists("./collada_world_exporter_lights_test")); + + // Cleanup + common::removeAll("./collada_world_exporter_lights_test"); +} + ///////////////////////////////////////////////// /// Main int main(int _argc, char **_argv) diff --git a/test/worlds/collada_world_exporter_lights.sdf b/test/worlds/collada_world_exporter_lights.sdf new file mode 100644 index 00000000000..bc5ac45460f --- /dev/null +++ b/test/worlds/collada_world_exporter_lights.sdf @@ -0,0 +1,177 @@ + + + + + + + + + true + + + + + 0 0 1 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 0 0 0.5 0 0 0 + + + + 1 + 0 + 0 + 1 + 0 + 1 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + + + 0 -1.5 0.5 0 0 0 + + + + 2 + 0 + 0 + 2 + 0 + 2 + + 2.0 + + + + + 0.5 + 1.0 + + + + + + + + 0.5 + 1.0 + + + + 0 1 0 1 + 0 1 0 1 + 0 1 0 1 + + + + + + + 0 1.5 0.5 0 0 0 + + + + 3 + 0 + 0 + 3 + 0 + 3 + + 3.0 + + + + + 0.5 + + + + + + + + 0.5 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + + + 0 2 2 0 0 0 + 1 0 0 1 + .1 .1 .1 1 + + 20 + 0.2 + 0.8 + 0.01 + + false + + + + true + 0 0 5 0 45 0 + 0.8 0.8 0.8 1 + 0.2 0.2 0.2 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + +