diff --git a/include/gz/sim/InstallationDirectories.hh b/include/gz/sim/InstallationDirectories.hh new file mode 100644 index 0000000000..08e3b2b29e --- /dev/null +++ b/include/gz/sim/InstallationDirectories.hh @@ -0,0 +1,57 @@ +/* + * Copyright (C) 2023 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 GZ_SIM_INSTALLATION_DIRECTORIES_HH_ +#define GZ_SIM_INSTALLATION_DIRECTORIES_HH_ + +#include + +#include +#include + +namespace gz +{ + namespace sim + { + inline namespace GZ_SIM_VERSION_NAMESPACE { + + /// \brief getInstallPrefix return the install prefix of the library + /// i.e. CMAKE_INSTALL_PREFIX unless the library has been moved + GZ_SIM_VISIBLE std::string getInstallPrefix(); + + /// \brief getGUIConfigPath return the GUI config path + GZ_SIM_VISIBLE std::string getGUIConfigPath(); + + /// \brief getSystemConfigPath return the system config path + GZ_SIM_VISIBLE std::string getSystemConfigPath(); + + /// \brief getServerConfigPath return the server config path + GZ_SIM_VISIBLE std::string getServerConfigPath(); + + /// \brief getPluginInstallDir return the plugin install dir + GZ_SIM_VISIBLE std::string getPluginInstallDir(); + + /// \brief getGUIPluginInstallDir return the GUI plugin install dir + GZ_SIM_VISIBLE std::string getGUIPluginInstallDir(); + + /// \brief getWorldInstallDir return the world install dir + GZ_SIM_VISIBLE std::string getWorldInstallDir(); + } + } +} + +#endif diff --git a/include/gz/sim/config.hh.in b/include/gz/sim/config.hh.in index 894bd0d754..a13b62aa1e 100644 --- a/include/gz/sim/config.hh.in +++ b/include/gz/sim/config.hh.in @@ -33,12 +33,12 @@ #define GZ_SIM_VERSION_HEADER "Gazebo Sim, version ${PROJECT_VERSION_FULL}\nCopyright (C) 2018 Open Source Robotics Foundation.\nReleased under the Apache 2.0 License.\n\n" -#define GZ_SIM_GUI_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/gui" -#define GZ_SIM_SYSTEM_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/systems" -#define GZ_SIM_SERVER_CONFIG_PATH "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}" -#define GZ_SIM_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" -#define GZ_SIM_GUI_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" -#define GZ_SIM_WORLD_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/worlds" +#define GZ_SIM_GUI_CONFIG_PATH _Pragma ("GCC warning \"'GZ_SIM_GUI_CONFIG_PATH' macro is deprecated, use gz::sim::getGUIConfigPath() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/gui" +#define GZ_SIM_SYSTEM_CONFIG_PATH _Pragma ("GCC warning \"'GZ_SIM_SYSTEM_CONFIG_PATH' macro is deprecated, use gz::sim::getSystemConfigPath() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/systems" +#define GZ_SIM_SERVER_CONFIG_PATH _Pragma ("GCC warning \"'GZ_SIM_SERVER_CONFIG_PATH' macro is deprecated, use gz::sim::getServerConfigPath() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}" +#define GZ_SIM_PLUGIN_INSTALL_DIR _Pragma ("GCC warning \"'GZ_SIM_PLUGIN_INSTALL_DIR' macro is deprecated, use gz::sim::getPluginInstallDir() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" +#define GZ_SIM_GUI_PLUGIN_INSTALL_DIR _Pragma ("GCC warning \"'GZ_SIM_GUI_PLUGIN_INSTALL_DIR' macro is deprecated, use gz::sim::getGUIPluginInstallDir() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" +#define GZ_SIM_WORLD_INSTALL_DIR _Pragma ("GCC warning \"'GZ_SIM_WORLD_INSTALL_DIR' macro is deprecated, use gz::sim::getWorldInstallDir() function instead. \"") "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/worlds" #define GZ_DISTRIBUTION "${GZ_DISTRIBUTION}" #endif diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 7f35532ce1..fe188f1c48 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -54,6 +54,7 @@ set (sources ComponentFactory.cc EntityComponentManager.cc EntityComponentManagerDiff.cc + InstallationDirectories.cc Joint.cc LevelManager.cc Light.cc @@ -168,6 +169,21 @@ target_link_libraries(${gz_lib_target} # Create the library target gz_create_core_library(SOURCES ${sources} CXX_STANDARD 17) +gz_add_get_install_prefix_impl(GET_INSTALL_PREFIX_FUNCTION gz::sim::getInstallPrefix + GET_INSTALL_PREFIX_HEADER gz/sim/InstallationDirectories.hh + OVERRIDE_INSTALL_PREFIX_ENV_VARIABLE GZ_SIM_INSTALL_PREFIX) + +set_property( + SOURCE InstallationDirectories.cc + PROPERTY COMPILE_DEFINITIONS + GZ_SIM_GUI_CONFIG_RELATIVE_PATH="${GZ_DATA_INSTALL_DIR}/gui" + GZ_SIM_SYSTEM_CONFIG_RELATIVE_PATH="${GZ_DATA_INSTALL_DIR}/systems" + GZ_SIM_SERVER_CONFIG_RELATIVE_PATH="${GZ_DATA_INSTALL_DIR}" + GZ_SIM_PLUGIN_RELATIVE_INSTALL_DIR="${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins" + GZ_SIM_GUI_PLUGIN_RELATIVE_INSTALL_DIR="${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui" + GZ_SIM_WORLD_RELATIVE_INSTALL_DIR="${GZ_DATA_INSTALL_DIR}/worlds" +) + target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} PUBLIC gz-math${GZ_MATH_VER} @@ -213,6 +229,8 @@ gz_build_tests(TYPE UNIT ${PROJECT_LIBRARY_TARGET_NAME} ${EXTRA_TEST_LIB_DEPS} gz-sim${PROJECT_VERSION_MAJOR} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) # Some server unit tests require rendering. diff --git a/src/InstallationDirectories.cc b/src/InstallationDirectories.cc new file mode 100644 index 0000000000..2aa64e334d --- /dev/null +++ b/src/InstallationDirectories.cc @@ -0,0 +1,67 @@ +/* + * Copyright (C) 2023 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +#include +#include + +#include + +namespace gz +{ +namespace sim +{ +inline namespace GZ_SIM_VERSION_NAMESPACE { + +std::string getGUIConfigPath() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_GUI_CONFIG_RELATIVE_PATH); +} + +std::string getSystemConfigPath() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_SYSTEM_CONFIG_RELATIVE_PATH); +} + +std::string getServerConfigPath() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_SERVER_CONFIG_RELATIVE_PATH); +} + +std::string getPluginInstallDir() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_PLUGIN_RELATIVE_INSTALL_DIR); +} + +std::string getGUIPluginInstallDir() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_GUI_PLUGIN_RELATIVE_INSTALL_DIR); +} + +std::string getWorldInstallDir() +{ + return gz::common::joinPaths( + getInstallPrefix(), GZ_SIM_WORLD_RELATIVE_INSTALL_DIR); +} + +} +} +} diff --git a/src/ServerConfig.cc b/src/ServerConfig.cc index b7e79b0cde..59af90581b 100644 --- a/src/ServerConfig.cc +++ b/src/ServerConfig.cc @@ -25,6 +25,7 @@ #include #include +#include "gz/sim/InstallationDirectories.hh" #include "gz/sim/Util.hh" using namespace gz; @@ -265,7 +266,8 @@ class gz::sim::ServerConfigPrivate networkSecondaries(_cfg->networkSecondaries), seed(_cfg->seed), logRecordTopics(_cfg->logRecordTopics), - isHeadlessRendering(_cfg->isHeadlessRendering) { } + isHeadlessRendering(_cfg->isHeadlessRendering), + source(_cfg->source){ } // \brief The SDF file that the server should load public: std::string sdfFile = ""; @@ -811,6 +813,7 @@ ServerConfig::SourceType ServerConfig::Source() const } ///////////////////////////////////////////////// +namespace { void copyElement(sdf::ElementPtr _sdf, const tinyxml2::XMLElement *_xml) { _sdf->SetName(_xml->Value()); @@ -917,6 +920,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc) } return ret; } +} // namespace ///////////////////////////////////////////////// std::list @@ -1013,7 +1017,7 @@ sim::loadPluginInfo(bool _isPlayback) if (!common::exists(defaultConfig)) { auto installedConfig = common::joinPaths( - GZ_SIM_SERVER_CONFIG_PATH, + gz::sim::getServerConfigPath(), configFilename); if (!common::createDirectories(defaultConfigDir)) diff --git a/src/SystemLoader.cc b/src/SystemLoader.cc index 90d86748e2..d68e8d4819 100644 --- a/src/SystemLoader.cc +++ b/src/SystemLoader.cc @@ -32,6 +32,7 @@ #include +#include "gz/sim/InstallationDirectories.hh" #include using namespace gz::sim; @@ -54,12 +55,12 @@ class gz::sim::SystemLoaderPrivate common::env(GZ_HOMEDIR, homePath); systemPaths.AddPluginPaths(common::joinPaths( homePath, ".gz", "sim", "plugins")); - systemPaths.AddPluginPaths(GZ_SIM_PLUGIN_INSTALL_DIR); + systemPaths.AddPluginPaths(gz::sim::getPluginInstallDir()); // TODO(CH3): Deprecated. Remove on tock. systemPaths.AddPluginPaths(homePath + "/.ignition/gazebo/plugins"); - systemPaths.AddPluginPaths(GZ_SIM_PLUGIN_INSTALL_DIR); + systemPaths.AddPluginPaths(gz::sim::getPluginInstallDir()); return systemPaths.PluginPaths(); } diff --git a/src/SystemLoader_TEST.cc b/src/SystemLoader_TEST.cc index b654924f34..4709af5fd8 100644 --- a/src/SystemLoader_TEST.cc +++ b/src/SystemLoader_TEST.cc @@ -97,9 +97,8 @@ TEST(SystemLoader, PluginPaths) for (const auto &s : paths) { // the returned path string may not be exact match due to extra '/' - // appended at the end of the string. So use absPath to generate - // a path string that matches the format returned by joinPaths - if (common::absPath(s) == testBuildPath) + // appended at the end of the string. So use absPath to compare paths + if (common::absPath(s) == common::absPath(testBuildPath)) { hasPath = true; break; diff --git a/src/Util.cc b/src/Util.cc index 552c68b2e1..db9918272f 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -49,6 +49,7 @@ #include "gz/sim/components/World.hh" #include "gz/sim/components/LinearVelocity.hh" +#include "gz/sim/InstallationDirectories.hh" #include "gz/sim/Util.hh" namespace gz @@ -829,7 +830,7 @@ std::string resolveSdfWorldFile(const std::string &_sdfFile, systemPaths.SetFilePathEnv(kResourcePathEnv); // Worlds installed with gz-sim - systemPaths.AddFilePaths(GZ_SIM_WORLD_INSTALL_DIR); + systemPaths.AddFilePaths(gz::sim::getWorldInstallDir()); filePath = systemPaths.FindFile(_sdfFile); } diff --git a/src/gui/CMakeLists.txt b/src/gui/CMakeLists.txt index 0f774b50f2..472eba232d 100644 --- a/src/gui/CMakeLists.txt +++ b/src/gui/CMakeLists.txt @@ -75,6 +75,8 @@ gz_build_tests(TYPE UNIT gz-sim${PROJECT_VERSION_MAJOR} gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER} gz-transport${GZ_TRANSPORT_VER}::gz-transport${GZ_TRANSPORT_VER} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) if(TARGET UNIT_Gui_clean_exit_TEST) diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc index f7ff4f0d8f..ef95a468d3 100644 --- a/src/gui/Gui.cc +++ b/src/gui/Gui.cc @@ -29,6 +29,7 @@ #include #include +#include "gz/sim/InstallationDirectories.hh" #include "gz/sim/Util.hh" #include "gz/sim/config.hh" #include "gz/sim/gui/Gui.hh" @@ -92,7 +93,7 @@ std::string defaultGuiConfigFile(bool _isPlayback, } auto installedConfig = common::joinPaths( - GZ_SIM_GUI_CONFIG_PATH, defaultGuiConfigName); + gz::sim::getGUIConfigPath(), defaultGuiConfigName); if (!common::copyFile(installedConfig, defaultConfig)) { gzerr << "Failed to copy installed config [" << installedConfig @@ -275,7 +276,7 @@ std::unique_ptr createGui( auto app = std::make_unique( _argc, _argv, gz::gui::WindowType::kMainWindow); - app->AddPluginPath(GZ_SIM_GUI_PLUGIN_INSTALL_DIR); + app->AddPluginPath(gz::sim::getGUIPluginInstallDir()); auto aboutDialogHandler = new gz::sim::gui::AboutDialogHandler(); aboutDialogHandler->setParent(app->Engine()); @@ -287,7 +288,7 @@ std::unique_ptr createGui( pathManager->setParent(app->Engine()); // add import path so we can load custom modules - app->Engine()->addImportPath(GZ_SIM_GUI_PLUGIN_INSTALL_DIR); + app->Engine()->addImportPath(gz::sim::getGUIPluginInstallDir().c_str()); app->SetDefaultConfigPath(defaultConfig); diff --git a/src/gui/QuickStartHandler.cc b/src/gui/QuickStartHandler.cc index c420bffc64..8659b2756d 100644 --- a/src/gui/QuickStartHandler.cc +++ b/src/gui/QuickStartHandler.cc @@ -17,13 +17,16 @@ #include "QuickStartHandler.hh" +#include "gz/sim/InstallationDirectories.hh" + using namespace gz; using namespace sim::gui; ///////////////////////////////////////////////// QString QuickStartHandler::WorldsPath() const { - return QString::fromUtf8(this->worldsPath.c_str()); + std::string worldsPathLocal = gz::sim::getWorldInstallDir(); + return QString::fromUtf8(worldsPathLocal.c_str()); } ///////////////////////////////////////////////// diff --git a/src/gui/QuickStartHandler.hh b/src/gui/QuickStartHandler.hh index e4648b5bb8..5814adce08 100644 --- a/src/gui/QuickStartHandler.hh +++ b/src/gui/QuickStartHandler.hh @@ -68,7 +68,9 @@ class GZ_SIM_GUI_VISIBLE QuickStartHandler : public QObject private: bool showAgain{true}; /// \brief Installed worlds path. - private: std::string worldsPath{GZ_SIM_WORLD_INSTALL_DIR}; + /// \warning This variable is unused and can be removed + /// once an ABI break is allowed + private: std::string worldsPath{""}; /// \brief Get starting world url. private: std::string startingWorld{""}; diff --git a/src/gui/plugins/CMakeLists.txt b/src/gui/plugins/CMakeLists.txt index 956158f39c..2a837a3e0e 100644 --- a/src/gui/plugins/CMakeLists.txt +++ b/src/gui/plugins/CMakeLists.txt @@ -118,7 +118,9 @@ function(gz_add_gui_plugin plugin_name) # Used to make test-directory headers visible to the unit tests ${PROJECT_SOURCE_DIR} # Used to make test_config.h visible to the unit tests - ${PROJECT_BINARY_DIR}) + ${PROJECT_BINARY_DIR} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX}) endif() endif() diff --git a/src/gui/plugins/component_inspector/ComponentInspector.cc b/src/gui/plugins/component_inspector/ComponentInspector.cc index ad261fb93f..cd5f0eadc3 100644 --- a/src/gui/plugins/component_inspector/ComponentInspector.cc +++ b/src/gui/plugins/component_inspector/ComponentInspector.cc @@ -1215,7 +1215,7 @@ void ComponentInspector::QuerySystems() "/system/info"}; if (!this->dataPtr->node.Request(service, req, timeout, res, result)) { - ignerr << "Unable to query available systems." << std::endl; + gzerr << "Unable to query available systems." << std::endl; return; } @@ -1225,8 +1225,8 @@ void ComponentInspector::QuerySystems() { if (plugin.filename().empty()) { - ignerr << "Received empty plugin name. This shouldn't happen." - << std::endl; + gzerr << "Received empty plugin name. This shouldn't happen." + << std::endl; continue; } @@ -1273,7 +1273,7 @@ void ComponentInspector::OnAddSystem(const QString &_name, auto it = this->dataPtr->systemMap.find(filenameStr); if (it == this->dataPtr->systemMap.end()) { - ignerr << "Internal error: failed to find [" << filenameStr + gzerr << "Internal error: failed to find [" << filenameStr << "] in system map." << std::endl; return; } @@ -1296,11 +1296,11 @@ void ComponentInspector::OnAddSystem(const QString &_name, "/entity/system/add"}; if (!this->dataPtr->node.Request(service, req, timeout, res, result)) { - ignerr << "Error adding new system to entity: " - << this->dataPtr->entity << "\n" - << "Name: " << name << "\n" - << "Filename: " << filename << "\n" - << "Inner XML: " << innerxml << std::endl; + gzerr << "Error adding new system to entity: " + << this->dataPtr->entity << "\n" + << "Name: " << name << "\n" + << "Filename: " << filename << "\n" + << "Inner XML: " << innerxml << std::endl; } } diff --git a/src/gz.cc b/src/gz.cc index aa0f908518..cd71e586bf 100644 --- a/src/gz.cc +++ b/src/gz.cc @@ -33,6 +33,7 @@ #include #include "gz/sim/config.hh" +#include "gz/sim/InstallationDirectories.hh" #include "gz/sim/Server.hh" #include "gz/sim/ServerConfig.hh" @@ -70,7 +71,8 @@ extern "C" void cmdVerbosity( ////////////////////////////////////////////////// extern "C" const char *worldInstallDir() { - return GZ_SIM_WORLD_INSTALL_DIR; + static std::string worldInstallDir = gz::sim::getWorldInstallDir(); + return worldInstallDir.c_str(); } ////////////////////////////////////////////////// diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 3c5e3da2d3..e86c31c117 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -1266,7 +1266,7 @@ void RenderUtil::Update() } else { - ignerr << "Failed to create light" << std::endl; + gzerr << "Failed to create light" << std::endl; } } diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 55d10e9534..f1f758e8e9 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -1191,7 +1191,7 @@ rendering::LightPtr SceneManager::CreateLight(Entity _id, if (this->HasEntity(_id)) { - ignerr << "Light with Id: [" << _id << "] can not be create there is " + gzerr << "Light with Id: [" << _id << "] can not be create there is " "another entity with the same entity number" << std::endl; return nullptr; } @@ -2376,8 +2376,8 @@ SceneManager::LoadAnimations(const sdf::Actor &_actor) { if (!meshSkel->AddBvhAnimation(animFilename, animScale)) { - ignerr << "Bvh animation in file " << animFilename - << " failed to load during actor creation" << std::endl; + gzerr << "Bvh animation in file " << animFilename + << " failed to load during actor creation" << std::endl; continue; } } @@ -2473,8 +2473,8 @@ SceneManagerPrivate::LoadTrajectories(const sdf::Actor &_actor, const sdf::Trajectory *trajSdf = _actor.TrajectoryByIndex(i); if (nullptr == trajSdf) { - ignerr << "Null trajectory SDF for [" << _actor.Name() << "]" - << std::endl; + gzerr << "Null trajectory SDF for [" << _actor.Name() << "]" + << std::endl; continue; } common::TrajectoryInfo trajInfo; @@ -2517,9 +2517,9 @@ SceneManagerPrivate::LoadTrajectories(const sdf::Actor &_actor, } else { - ignwarn << "Animation has no x displacement. " - << "Ignoring for the animation in '" - << animation->Filename() << "'." << std::endl; + gzwarn << "Animation has no x displacement. " + << "Ignoring for the animation in '" + << animation->Filename() << "'." << std::endl; } animInterpolateCheck.insert(animation->Filename()); } diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.cc b/src/systems/battery_plugin/LinearBatteryPlugin.cc index 8f7cc41eb1..7dcf38bc3f 100644 --- a/src/systems/battery_plugin/LinearBatteryPlugin.cc +++ b/src/systems/battery_plugin/LinearBatteryPlugin.cc @@ -394,8 +394,8 @@ void LinearBatteryPlugin::Configure(const Entity &_entity, std::bind(&LinearBatteryPluginPrivate::OnBatteryStopDrainingMsg, this->dataPtr.get(), std::placeholders::_1, std::placeholders::_2, std::placeholders::_3)); - ignmsg << "LinearBatteryPlugin subscribes to stop power draining topic [" - << topic << "]." << std::endl; + gzmsg << "LinearBatteryPlugin subscribes to stop power draining topic [" + << topic << "]." << std::endl; sdfElem = sdfElem->GetNextElement("power_draining_topic"); } } @@ -498,7 +498,7 @@ void LinearBatteryPlugin::PreUpdate( bool success = this->dataPtr->battery->SetPowerLoad( this->dataPtr->consumerId, total_power_load); if (!success) - ignerr << "Failed to set consumer power load." << std::endl; + gzerr << "Failed to set consumer power load." << std::endl; // Start draining the battery if the robot has started moving if (!this->dataPtr->startDraining) diff --git a/src/systems/buoyancy/Buoyancy.cc b/src/systems/buoyancy/Buoyancy.cc index a2c21b9c5a..5bd0ae54b4 100644 --- a/src/systems/buoyancy/Buoyancy.cc +++ b/src/systems/buoyancy/Buoyancy.cc @@ -643,7 +643,7 @@ void Buoyancy::PostUpdate( bool Buoyancy::IsEnabled(Entity _entity, const EntityComponentManager &_ecm) const { - return this->IsEnabled(_entity, _ecm); + return this->dataPtr->IsEnabled(_entity, _ecm); } GZ_ADD_PLUGIN(Buoyancy, diff --git a/src/systems/environment_preload/EnvironmentPreload.cc b/src/systems/environment_preload/EnvironmentPreload.cc index fe5b57f940..5c678aa2db 100644 --- a/src/systems/environment_preload/EnvironmentPreload.cc +++ b/src/systems/environment_preload/EnvironmentPreload.cc @@ -134,7 +134,7 @@ void EnvironmentPreload::PreUpdate( } else if (unitName != "radians") { - ignerr << "Unrecognized unit " << unitName << "\n"; + gzerr << "Unrecognized unit " << unitName << "\n"; } } } diff --git a/src/systems/environmental_sensor_system/CMakeLists.txt b/src/systems/environmental_sensor_system/CMakeLists.txt index c589a464bf..ff91c6e175 100644 --- a/src/systems/environmental_sensor_system/CMakeLists.txt +++ b/src/systems/environmental_sensor_system/CMakeLists.txt @@ -12,4 +12,6 @@ gz_build_tests(TYPE UNIT TransformTypes_TEST.cc LIB_DEPS gz-math${GZ_MATH_VER}::gz-math${GZ_MATH_VER} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/src/systems/hydrodynamics/Hydrodynamics.cc b/src/systems/hydrodynamics/Hydrodynamics.cc index ba54d315eb..e657ad8bb5 100644 --- a/src/systems/hydrodynamics/Hydrodynamics.cc +++ b/src/systems/hydrodynamics/Hydrodynamics.cc @@ -295,7 +295,7 @@ void Hydrodynamics::Configure( { if (_sdf->HasElement("waterDensity")) { - ignwarn << + gzwarn << " parameter is deprecated and will be removed Ignition G.\n" << "\tPlease update your SDF to use instead."; } @@ -342,7 +342,7 @@ void Hydrodynamics::Configure( if (warnBehaviourChange) { - ignwarn << "You are using parameters that may cause instabilities " + gzwarn << "You are using parameters that may cause instabilities " << "in your simulation. If your simulation crashes we recommend " << "renaming -> and likewise for other axis " << "for more information see:" << std::endl diff --git a/src/systems/logical_audio_sensor_plugin/CMakeLists.txt b/src/systems/logical_audio_sensor_plugin/CMakeLists.txt index 607c0705d0..9bd43e073e 100644 --- a/src/systems/logical_audio_sensor_plugin/CMakeLists.txt +++ b/src/systems/logical_audio_sensor_plugin/CMakeLists.txt @@ -18,4 +18,6 @@ gz_build_tests(TYPE UNIT ${gtest_sources} LIB_DEPS ${PROJECT_LIBRARY_TARGET_NAME}-logicalaudiosensorplugin-system + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/src/systems/multicopter_control/MulticopterVelocityControl.hh b/src/systems/multicopter_control/MulticopterVelocityControl.hh index 2c1f4b37af..c414d1ec53 100644 --- a/src/systems/multicopter_control/MulticopterVelocityControl.hh +++ b/src/systems/multicopter_control/MulticopterVelocityControl.hh @@ -21,6 +21,9 @@ #include #include +#include +#include +#include #include #include diff --git a/src/systems/performer_detector/PerformerDetector.hh b/src/systems/performer_detector/PerformerDetector.hh index 84c8e12d9c..bbdb9e3ddf 100644 --- a/src/systems/performer_detector/PerformerDetector.hh +++ b/src/systems/performer_detector/PerformerDetector.hh @@ -23,6 +23,7 @@ #include #include +#include #include #include "gz/sim/Model.hh" diff --git a/src/systems/physics/CMakeLists.txt b/src/systems/physics/CMakeLists.txt index ad18e3f494..006fe39fa4 100644 --- a/src/systems/physics/CMakeLists.txt +++ b/src/systems/physics/CMakeLists.txt @@ -27,4 +27,6 @@ gz_build_tests(TYPE UNIT ${gtest_sources} LIB_DEPS gz-physics${GZ_PHYSICS_VER}::core + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 8fa201a12a..c70e2103db 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -3763,8 +3763,7 @@ void PhysicsPrivate::UpdateCollisions(EntityComponentManager &_ecm) // Note that we are temporarily storing pointers to elements in this // ("allContacts") container. Thus, we must make sure it doesn't get destroyed // until the end of this function. - auto allContacts = - std::move(worldCollisionFeature->GetContactsFromLastStep()); + auto allContacts = worldCollisionFeature->GetContactsFromLastStep(); for (const auto &contactComposite : allContacts) { diff --git a/src/systems/sensors/Sensors.cc b/src/systems/sensors/Sensors.cc index 4790345300..a346076f6d 100644 --- a/src/systems/sensors/Sensors.cc +++ b/src/systems/sensors/Sensors.cc @@ -280,12 +280,15 @@ void SensorsPrivate::RunOnce() { { std::unique_lock cvLock(this->renderMutex); - this->renderCv.wait(cvLock, [this]() + this->renderCv.wait_for(cvLock, std::chrono::microseconds(1000), [this]() { return !this->running || this->updateAvailable; }); } + if (!this->updateAvailable) + return; + if (!this->running) return; @@ -621,7 +624,7 @@ void Sensors::Update(const UpdateInfo &_info, _ecm.HasComponentType(components::WideAngleCamera::typeId))) { std::unique_lock lock(this->dataPtr->renderMutex); - igndbg << "Initialization needed" << std::endl; + gzdbg << "Initialization needed" << std::endl; this->dataPtr->renderUtil.Init(); this->dataPtr->nextUpdateTime = _info.simTime; } diff --git a/src/systems/thruster/Thruster.cc b/src/systems/thruster/Thruster.cc index c8a4492210..30b1a3e2b1 100644 --- a/src/systems/thruster/Thruster.cc +++ b/src/systems/thruster/Thruster.cc @@ -451,7 +451,7 @@ void Thruster::Configure( { if (!_sdf->HasElement("battery_name")) { - ignerr << "Specified a but missing ." + gzerr << "Specified a but missing ." "Specify a battery name so the power load can be assigned to it." << std::endl; } @@ -586,17 +586,17 @@ void Thruster::PreUpdate( }); if (numBatteriesWithName == 0) { - ignerr << "Can't assign battery consumption to battery: [" - << this->dataPtr->batteryName << "]. No batteries" - "were found with the given name." << std::endl; + gzerr << "Can't assign battery consumption to battery: [" + << this->dataPtr->batteryName << "]. No batteries" + "were found with the given name." << std::endl; return; } if (numBatteriesWithName > 1) { - ignerr << "More than one battery found with name: [" - << this->dataPtr->batteryName << "]. Please make" - "sure battery names are unique within the system." - << std::endl; + gzerr << "More than one battery found with name: [" + << this->dataPtr->batteryName << "]. Please make" + "sure battery names are unique within the system." + << std::endl; return; } diff --git a/src/systems/triggered_publisher/TriggeredPublisher.cc b/src/systems/triggered_publisher/TriggeredPublisher.cc index 87d0add654..80c92981c2 100644 --- a/src/systems/triggered_publisher/TriggeredPublisher.cc +++ b/src/systems/triggered_publisher/TriggeredPublisher.cc @@ -605,31 +605,31 @@ void TriggeredPublisher::Configure(const Entity &, serviceInfo.srvName = serviceElem->Get("name"); if (serviceInfo.srvName.empty()) { - ignerr << "Service name cannot be empty\n"; + gzerr << "Service name cannot be empty\n"; return; } serviceInfo.reqType = serviceElem->Get("reqType"); if (serviceInfo.reqType.empty()) { - ignerr << "Service request type cannot be empty\n"; + gzerr << "Service request type cannot be empty\n"; return; } serviceInfo.repType = serviceElem->Get("repType"); if (serviceInfo.repType.empty()) { - ignerr << "Service reply type cannot be empty\n"; + gzerr << "Service reply type cannot be empty\n"; return; } serviceInfo.reqMsg = serviceElem->Get("reqMsg"); if (serviceInfo.reqMsg.empty()) { - ignerr << "Service request message cannot be empty\n"; + gzerr << "Service request message cannot be empty\n"; return; } std::string timeoutInfo = serviceElem->Get("timeout"); if (timeoutInfo.empty()) { - ignerr << "Timeout value cannot be empty\n"; + gzerr << "Timeout value cannot be empty\n"; return; } @@ -639,7 +639,7 @@ void TriggeredPublisher::Configure(const Entity &, } if (!sdfClone->HasElement("service") && !sdfClone->HasElement("output")) { - ignerr << "No output and service specified. Make sure to specify at least" + gzerr << "No output and service specified. Make sure to specify at least" "one of them." << std::endl; return; } @@ -715,16 +715,16 @@ void TriggeredPublisher::CallService(std::size_t pendingSrv) auto req = msgs::Factory::New(serviceInfo.reqType, serviceInfo.reqMsg); if (!req) { - ignerr << "Unable to create request for type [" - << serviceInfo.reqType << "].\n"; + gzerr << "Unable to create request for type [" + << serviceInfo.reqType << "].\n"; return; } auto rep = msgs::Factory::New(serviceInfo.repType); if (!rep) { - ignerr << "Unable to create response for type [" - << serviceInfo.repType << "].\n"; + gzerr << "Unable to create response for type [" + << serviceInfo.repType << "].\n"; return; } @@ -734,16 +734,16 @@ void TriggeredPublisher::CallService(std::size_t pendingSrv) { if (!result) { - ignerr << "Service call [" << serviceInfo.srvName << "] failed\n"; + gzerr << "Service call [" << serviceInfo.srvName << "] failed\n"; } else { - ignmsg << "Service call [" << serviceInfo.srvName << "] succeeded\n"; + gzmsg << "Service call [" << serviceInfo.srvName << "] succeeded\n"; } } else { - ignerr << "Service call [" << serviceInfo.srvName << "] timed out\n"; + gzerr << "Service call [" << serviceInfo.srvName << "] timed out\n"; } } } diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index df21fb46ec..d702cd4012 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -148,6 +148,8 @@ gz_build_tests(TYPE INTEGRATION ${tests} LIB_DEPS ${EXTRA_TEST_LIB_DEPS} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/test/integration/log_system.cc b/test/integration/log_system.cc index 54032c013f..fa3ba96734 100644 --- a/test/integration/log_system.cc +++ b/test/integration/log_system.cc @@ -1669,7 +1669,7 @@ TEST_F(LogSystemTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(RecordPeriod)) #ifndef __APPLE__ // Log from command line { - // Command line triggers ign.cc, which handles initializing ignLogDirectory + // Command line triggers gz.cc, which handles initializing gzlogDirectory std::string cmd = kGzCommand + " -r -v 4 --iterations " + std::to_string(numIterations) + " " + "--record-period 0.002 " diff --git a/test/performance/CMakeLists.txt b/test/performance/CMakeLists.txt index 81cbd25f75..b43c3cba4f 100644 --- a/test/performance/CMakeLists.txt +++ b/test/performance/CMakeLists.txt @@ -41,6 +41,8 @@ gz_build_tests(TYPE PERFORMANCE ${tests} LIB_DEPS ${EXTRA_TEST_LIB_DEPS} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) add_executable( diff --git a/test/regression/CMakeLists.txt b/test/regression/CMakeLists.txt index cad4ba516d..126c2b66b4 100644 --- a/test/regression/CMakeLists.txt +++ b/test/regression/CMakeLists.txt @@ -19,4 +19,6 @@ gz_build_tests(TYPE REGRESSION ${tests} LIB_DEPS ${EXTRA_TEST_LIB_DEPS} + ENVIRONMENT + GZ_SIM_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} ) diff --git a/test/test_config.hh.in b/test/test_config.hh.in index 4ccac6b3be..4681208058 100644 --- a/test/test_config.hh.in +++ b/test/test_config.hh.in @@ -18,6 +18,7 @@ #define GZ_SIM_TEST_CONFIG_HH_ #include +#include #include #define PROJECT_SOURCE_PATH "${PROJECT_SOURCE_DIR}" diff --git a/tutorials/battery.md b/tutorials/battery.md index fea877ca5e..c2156cbd0f 100644 --- a/tutorials/battery.md +++ b/tutorials/battery.md @@ -187,7 +187,7 @@ At the configure step the parameters are read and saved: { if (!_sdf->HasElement("battery_name")) { - ignerr << "Specified a but missing ." + gzerr << "Specified a but missing ." "Specify a battery name so the power load can be assigned to it." << std::endl; } @@ -246,14 +246,14 @@ are found with the specified name. ``` if (numBatteriesWithName == 0) { - ignerr << "Can't assign battery consumption to battery: [" + gzerr << "Can't assign battery consumption to battery: [" << this->dataPtr->batteryName << "]. No batteries" "were found with the given name." << std::endl; return; } if (numBatteriesWithName > 1) { - ignerr << "More than one battery found with name: [" + gzerr << "More than one battery found with name: [" << this->dataPtr->batteryName << "]. Please make" "sure battery names are unique within the system." << std::endl;