Skip to content

Commit

Permalink
Merge branch 'gz-sim7' into mabelzhang/categorize_tutorials
Browse files Browse the repository at this point in the history
  • Loading branch information
mabelzhang committed Jul 13, 2023
2 parents b6a95bd + b2c576b commit 40ea620
Show file tree
Hide file tree
Showing 36 changed files with 253 additions and 75 deletions.
57 changes: 57 additions & 0 deletions include/gz/sim/InstallationDirectories.hh
Original file line number Diff line number Diff line change
@@ -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 <string>

#include <gz/sim/config.hh>
#include <gz/sim/Export.hh>

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
12 changes: 6 additions & 6 deletions include/gz/sim/config.hh.in
Original file line number Diff line number Diff line change
Expand Up @@ -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
18 changes: 18 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ set (sources
ComponentFactory.cc
EntityComponentManager.cc
EntityComponentManagerDiff.cc
InstallationDirectories.cc
Joint.cc
LevelManager.cc
Light.cc
Expand Down Expand Up @@ -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}
Expand Down Expand Up @@ -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.
Expand Down
67 changes: 67 additions & 0 deletions src/InstallationDirectories.cc
Original file line number Diff line number Diff line change
@@ -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 <gz/sim/config.hh>
#include <gz/sim/InstallationDirectories.hh>

#include <gz/common/Filesystem.hh>

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);
}

}
}
}
8 changes: 6 additions & 2 deletions src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
#include <gz/fuel_tools/Result.hh>
#include <gz/math/Rand.hh>

#include "gz/sim/InstallationDirectories.hh"
#include "gz/sim/Util.hh"

using namespace gz;
Expand Down Expand Up @@ -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 = "";
Expand Down Expand Up @@ -811,6 +813,7 @@ ServerConfig::SourceType ServerConfig::Source() const
}

/////////////////////////////////////////////////
namespace {
void copyElement(sdf::ElementPtr _sdf, const tinyxml2::XMLElement *_xml)
{
_sdf->SetName(_xml->Value());
Expand Down Expand Up @@ -917,6 +920,7 @@ parsePluginsFromDoc(const tinyxml2::XMLDocument &_doc)
}
return ret;
}
} // namespace

/////////////////////////////////////////////////
std::list<ServerConfig::PluginInfo>
Expand Down Expand Up @@ -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))
Expand Down
5 changes: 3 additions & 2 deletions src/SystemLoader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@

#include <gz/plugin/Loader.hh>

#include "gz/sim/InstallationDirectories.hh"
#include <gz/sim/config.hh>

using namespace gz::sim;
Expand All @@ -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();
}
Expand Down
5 changes: 2 additions & 3 deletions src/SystemLoader_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
3 changes: 2 additions & 1 deletion src/Util.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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);
}
Expand Down
2 changes: 2 additions & 0 deletions src/gui/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
7 changes: 4 additions & 3 deletions src/gui/Gui.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <gz/gui/MainWindow.hh>
#include <gz/gui/Plugin.hh>

#include "gz/sim/InstallationDirectories.hh"
#include "gz/sim/Util.hh"
#include "gz/sim/config.hh"
#include "gz/sim/gui/Gui.hh"
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -275,7 +276,7 @@ std::unique_ptr<gz::gui::Application> createGui(
auto app = std::make_unique<gz::gui::Application>(
_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());
Expand All @@ -287,7 +288,7 @@ std::unique_ptr<gz::gui::Application> 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);

Expand Down
5 changes: 4 additions & 1 deletion src/gui/QuickStartHandler.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
}

/////////////////////////////////////////////////
Expand Down
4 changes: 3 additions & 1 deletion src/gui/QuickStartHandler.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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{""};
Expand Down
4 changes: 3 additions & 1 deletion src/gui/plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down
Loading

0 comments on commit 40ea620

Please sign in to comment.