diff --git a/include/ignition/gazebo/Server.hh b/include/ignition/gazebo/Server.hh index c9fc6685a3..cd7761b463 100644 --- a/include/ignition/gazebo/Server.hh +++ b/include/ignition/gazebo/Server.hh @@ -82,6 +82,12 @@ namespace ignition /// 1. /world//scene/info(none) : ignition::msgs::Scene /// + Returns the current scene information. /// + /// 2. /gazebo/resource_paths/get : ignition::msgs::StringMsg_V + /// + Get list of resource paths. + /// + /// 3. /gazebo/resource_paths/add : ignition::msgs::Empty + /// + Add new resource paths. + /// /// ## Topics /// /// The following are topics provided by the Server. @@ -95,6 +101,9 @@ namespace ignition /// 2. /world//stats : ignition::msgs::WorldStatistics /// + This topic is throttled to 5Hz. /// + /// 3. /gazebo/resource_paths : ignition::msgs::StringMsg_V + /// + Updated list of resource paths. + /// class IGNITION_GAZEBO_VISIBLE Server { /// \brief Construct the server using the parameters specified in a diff --git a/include/ignition/gazebo/Util.hh b/include/ignition/gazebo/Util.hh index 74943c03b0..87cc852779 100644 --- a/include/ignition/gazebo/Util.hh +++ b/include/ignition/gazebo/Util.hh @@ -18,6 +18,7 @@ #define IGNITION_GAZEBO_UTIL_HH_ #include +#include #include #include "ignition/gazebo/config.hh" @@ -66,8 +67,26 @@ namespace ignition /// paths. /// \param[in] _filePath The path to a file in disk. /// \return The full path URI. - std::string asFullPath(const std::string &_uri, + std::string IGNITION_GAZEBO_VISIBLE asFullPath(const std::string &_uri, const std::string &_filePath); + + /// \brief Get resource paths based on latest environment variables. + /// \return All paths in the IGN_GAZEBO_RESOURCE_PATH variable. + std::vector IGNITION_GAZEBO_VISIBLE resourcePaths(); + + /// \brief Add resource paths based on latest environment variables. + /// This will update the SDF and Ignition environment variables, and + /// optionally add more paths to the list. + /// \param[in] _paths Optional paths to add. + void IGNITION_GAZEBO_VISIBLE addResourcePaths( + const std::vector &_paths = {}); + + /// \brief Environment variable holding resource paths. + const std::string kResourcePathEnv{"IGN_GAZEBO_RESOURCE_PATH"}; + + /// \brief Environment variable used by SDFormat to find URIs inside + /// `` + const std::string kSdfPathEnv{"SDF_PATH"}; } } } diff --git a/src/SdfGenerator_TEST.cc b/src/SdfGenerator_TEST.cc index 2c50aec3ca..1eb9dcbcae 100644 --- a/src/SdfGenerator_TEST.cc +++ b/src/SdfGenerator_TEST.cc @@ -52,9 +52,17 @@ static bool isSubset(const sdf::ElementPtr &_elemA, const sdf::ElementPtr &_elemB) { if (_elemA->GetName() != _elemB->GetName()) + { + igndbg << "[" << _elemA->GetName() << "] different from [" + << _elemB->GetName() << "]" << std::endl; return false; + } if (_elemA->GetAttributeCount() != _elemB->GetAttributeCount()) + { + igndbg << "[" << _elemA->GetAttributeCount() << "] different from [" + << _elemB->GetAttributeCount() << "]" << std::endl; return false; + } // Compare attributes for (std::size_t i = 0; i < _elemA->GetAttributeCount(); ++i) @@ -62,9 +70,17 @@ static bool isSubset(const sdf::ElementPtr &_elemA, sdf::ParamPtr attrA = _elemA->GetAttribute(i); sdf::ParamPtr attrB = _elemB->GetAttribute(attrA->GetKey()); if (attrA->GetTypeName() != attrB->GetTypeName()) + { + igndbg << "[" << attrA->GetTypeName() << "] different from [" + << attrB->GetTypeName() << "]" << std::endl; return false; + } if (attrA->GetAsString() != attrB->GetAsString()) + { + igndbg << "[" << attrA->GetAsString() << "] different from [" + << attrB->GetAsString() << "]" << std::endl; return false; + } } // Compare values { diff --git a/src/Server.cc b/src/Server.cc index 8e0eff3545..be57513d8d 100644 --- a/src/Server.cc +++ b/src/Server.cc @@ -14,7 +14,6 @@ * limitations under the License. * */ -#include "ignition/gazebo/Server.hh" #include #include @@ -23,6 +22,9 @@ #include #include "ignition/gazebo/config.hh" +#include "ignition/gazebo/Server.hh" +#include "ignition/gazebo/Util.hh" + #include "ServerPrivate.hh" #include "SimulationRunner.hh" @@ -100,6 +102,8 @@ Server::Server(const ServerConfig &_config) common::addFindFileURICallback(std::bind(&ServerPrivate::FetchResourceUri, this->dataPtr.get(), std::placeholders::_1)); + addResourcePaths(); + sdf::Errors errors; // Load a world if specified. Check SDF string first, then SDF file @@ -120,7 +124,7 @@ Server::Server(const ServerConfig &_config) else if (!_config.SdfFile().empty()) { common::SystemPaths systemPaths; - systemPaths.SetFilePathEnv("IGN_GAZEBO_RESOURCE_PATH"); + systemPaths.SetFilePathEnv(kResourcePathEnv); systemPaths.AddFilePaths(IGN_GAZEBO_WORLD_INSTALL_DIR); std::string filePath = systemPaths.FindFile(_config.SdfFile()); ignmsg << "Loading SDF world file[" << filePath << "].\n"; diff --git a/src/ServerPrivate.cc b/src/ServerPrivate.cc index 1f49669602..b3f57e944e 100644 --- a/src/ServerPrivate.cc +++ b/src/ServerPrivate.cc @@ -22,11 +22,13 @@ #include #include +#include #include #include +#include "ignition/gazebo/Util.hh" #include "SimulationRunner.hh" using namespace ignition; @@ -384,7 +386,26 @@ void ServerPrivate::CreateEntities() void ServerPrivate::SetupTransport() { // Advertise available worlds. - this->node.Advertise("/gazebo/worlds", &ServerPrivate::WorldsService, this); + std::string worldsService{"/gazebo/worlds"}; + this->node.Advertise(worldsService, &ServerPrivate::WorldsService, this); + + ignmsg << "Serving world names on [" << worldsService << "]" << std::endl; + + // Resource path management + std::string addPathService{"/gazebo/resource_paths/add"}; + this->node.Advertise(addPathService, + &ServerPrivate::AddResourcePathsService, this); + + std::string getPathService{"/gazebo/resource_paths/get"}; + this->node.Advertise(getPathService, + &ServerPrivate::ResourcePathsService, this); + + std::string pathTopic{"/gazebo/resource_paths"}; + this->pathPub = this->node.Advertise(pathTopic); + + ignmsg << "Resource path interfaces on [" << addPathService + << "], [" << getPathService << "], and [" << pathTopic << "]." + << std::endl; } ////////////////////////////////////////////////// @@ -402,6 +423,49 @@ bool ServerPrivate::WorldsService(ignition::msgs::StringMsg_V &_res) return true; } +////////////////////////////////////////////////// +void ServerPrivate::AddResourcePathsService( + const ignition::msgs::StringMsg_V &_req) +{ + std::vector paths; + for (int i = 0; i < _req.data_size(); ++i) + { + paths.push_back(_req.data(i)); + } + addResourcePaths(paths); + + // Notify new paths + msgs::StringMsg_V msg; + auto gzPaths = resourcePaths(); + for (const auto &path : gzPaths) + { + if (!path.empty()) + msg.add_data(path); + } + + this->pathPub.Publish(msg); +} + +////////////////////////////////////////////////// +bool ServerPrivate::ResourcePathsService( + ignition::msgs::StringMsg_V &_res) +{ + _res.Clear(); + + // Update paths + addResourcePaths(); + + // Get paths + auto gzPaths = resourcePaths(); + for (const auto &path : gzPaths) + { + if (!path.empty()) + _res.add_data(path); + } + + return true; +} + ////////////////////////////////////////////////// std::string ServerPrivate::FetchResource(const std::string &_uri) { diff --git a/src/ServerPrivate.hh b/src/ServerPrivate.hh index 4f46c8d957..5ec908ec8a 100644 --- a/src/ServerPrivate.hh +++ b/src/ServerPrivate.hh @@ -103,6 +103,16 @@ namespace ignition /// \return True if successful. private: bool WorldsService(ignition::msgs::StringMsg_V &_res); + /// \brief Callback for add resource paths service. + /// \param[out] _req Request containing the paths to be added. + private: void AddResourcePathsService( + const ignition::msgs::StringMsg_V &_req); + + /// \brief Callback for get resource paths service. + /// \param[out] _res Response filled with all current paths. + /// \return True if successful. + private: bool ResourcePathsService(ignition::msgs::StringMsg_V &_res); + /// \brief A pool of worker threads. public: common::WorkerPool workerPool{2}; @@ -148,6 +158,9 @@ namespace ignition /// \brief Node for transport. private: transport::Node node; + + /// \brief Publisher of resrouce paths. + private: transport::Node::Publisher pathPub; }; } } diff --git a/src/Server_TEST.cc b/src/Server_TEST.cc index bc9397e13a..277de595ac 100644 --- a/src/Server_TEST.cc +++ b/src/Server_TEST.cc @@ -19,10 +19,15 @@ #include #include #include +#include #include #include #include +#include +#include "ignition/gazebo/components/AxisAlignedBox.hh" +#include "ignition/gazebo/components/Geometry.hh" +#include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/Entity.hh" #include "ignition/gazebo/EntityComponentManager.hh" #include "ignition/gazebo/System.hh" @@ -32,6 +37,7 @@ #include "ignition/gazebo/test_config.hh" #include "plugins/MockSystem.hh" +#include "../test/helpers/Relay.hh" using namespace ignition; using namespace ignition::gazebo; @@ -643,6 +649,185 @@ TEST_P(ServerFixture, Seed) EXPECT_EQ(mySeed, ignition::math::Rand::Seed()); } +///////////////////////////////////////////////// +TEST_P(ServerFixture, ResourcePath) +{ + setenv("IGN_GAZEBO_RESOURCE_PATH", + (std::string(PROJECT_SOURCE_PATH) + "/test/worlds:" + + std::string(PROJECT_SOURCE_PATH) + "/test/worlds/models").c_str(), 1); + + ServerConfig serverConfig; + serverConfig.SetSdfFile("resource_paths.sdf"); + gazebo::Server server(serverConfig); + + test::Relay testSystem; + unsigned int preUpdates{0}; + testSystem.OnPreUpdate( + [&preUpdates](const gazebo::UpdateInfo &, + gazebo::EntityComponentManager &_ecm) + { + // Create AABB so it is populated + unsigned int eachCount{0}; + _ecm.Each( + [&](const Entity &_entity, components::Model *) -> bool + { + auto bboxComp = _ecm.Component(_entity); + EXPECT_EQ(bboxComp, nullptr); + _ecm.CreateComponent(_entity, components::AxisAlignedBox()); + eachCount++; + return true; + }); + EXPECT_EQ(1u, eachCount); + preUpdates++; + }); + + unsigned int postUpdates{0}; + testSystem.OnPostUpdate([&postUpdates](const gazebo::UpdateInfo &, + const gazebo::EntityComponentManager &_ecm) + { + // Check geometry components + unsigned int eachCount{0}; + _ecm.Each( + [&eachCount](const Entity &, const components::Geometry *_geom) + -> bool + { + auto mesh = _geom->Data().MeshShape(); + + // ASSERT would fail at compile with + // "void value not ignored as it ought to be" + EXPECT_NE(nullptr, mesh); + + if (mesh) + { + EXPECT_EQ("model://scheme_resource_uri/meshes/box.dae", + mesh->Uri()); + } + + eachCount++; + return true; + }); + EXPECT_EQ(2u, eachCount); + + // Check physics system loaded meshes and got their BB correct + eachCount = 0; + _ecm.Each( + [&](const ignition::gazebo::Entity &, + const components::AxisAlignedBox *_box)->bool + { + auto box = _box->Data(); + EXPECT_EQ(box, math::AxisAlignedBox(-0.4, -0.4, 0.6, 0.4, 0.4, 1.4)); + eachCount++; + return true; + }); + EXPECT_EQ(1u, eachCount); + + postUpdates++; + }); + server.AddSystem(testSystem.systemPtr); + + EXPECT_FALSE(*server.Running(0)); + + EXPECT_TRUE(server.Run(true /*blocking*/, 1, false /*paused*/)); + EXPECT_EQ(1u, preUpdates); + EXPECT_EQ(1u, postUpdates); + + EXPECT_EQ(7u, *server.EntityCount()); + EXPECT_TRUE(server.HasEntity("scheme_resource_uri")); + EXPECT_TRUE(server.HasEntity("the_link")); + EXPECT_TRUE(server.HasEntity("the_visual")); +} + +///////////////////////////////////////////////// +TEST_P(ServerFixture, GetResourcePaths) +{ + setenv("IGN_GAZEBO_RESOURCE_PATH", + "/tmp/some/path:/home/user/another_path", 1); + + ServerConfig serverConfig; + gazebo::Server server(serverConfig); + + EXPECT_FALSE(*server.Running(0)); + + transport::Node node; + msgs::StringMsg_V res; + bool result; + bool executed = node.Request("/gazebo/resource_paths/get", 5000, res, result); + EXPECT_TRUE(executed); + EXPECT_TRUE(result); + EXPECT_EQ(2, res.data_size()); + EXPECT_EQ("/tmp/some/path", res.data(0)); + EXPECT_EQ("/home/user/another_path", res.data(1)); +} + +///////////////////////////////////////////////// +TEST_P(ServerFixture, AddResourcePaths) +{ + setenv("IGN_GAZEBO_RESOURCE_PATH", + "/tmp/some/path:/home/user/another_path", 1); + setenv("SDF_PATH", "", 1); + setenv("IGN_FILE_PATH", "", 1); + + ServerConfig serverConfig; + gazebo::Server server(serverConfig); + + EXPECT_FALSE(*server.Running(0)); + + transport::Node node; + + // Subscribe to path updates + bool receivedMsg{false}; + auto resourceCb = std::function( + [&receivedMsg](const auto &_msg) + { + receivedMsg = true; + EXPECT_EQ(5, _msg.data_size()); + EXPECT_EQ("/tmp/some/path", _msg.data(0)); + EXPECT_EQ("/home/user/another_path", _msg.data(1)); + EXPECT_EQ("/tmp/new_path", _msg.data(2)); + EXPECT_EQ("/tmp/more", _msg.data(3)); + EXPECT_EQ("/tmp/even_more", _msg.data(4)); + }); + node.Subscribe("/gazebo/resource_paths", resourceCb); + + // Add path + msgs::StringMsg_V req; + req.add_data("/tmp/new_path"); + req.add_data("/tmp/more:/tmp/even_more"); + req.add_data("/tmp/some/path"); + bool executed = node.Request("/gazebo/resource_paths/add", req); + EXPECT_TRUE(executed); + + int sleep{0}; + int maxSleep{30}; + while (!receivedMsg && sleep < maxSleep) + { + IGN_SLEEP_MS(50); + sleep++; + } + EXPECT_TRUE(receivedMsg); + + // Check environment variables + for (auto env : {"IGN_GAZEBO_RESOURCE_PATH", "SDF_PATH", "IGN_FILE_PATH"}) + { + char *pathCStr = getenv(env); + + auto paths = common::Split(pathCStr, ':'); + paths.erase(std::remove_if(paths.begin(), paths.end(), + [](std::string const &_path) + { + return _path.empty(); + }), + paths.end()); + + EXPECT_EQ(5u, paths.size()); + EXPECT_EQ("/tmp/some/path", paths[0]); + EXPECT_EQ("/home/user/another_path", paths[1]); + EXPECT_EQ("/tmp/new_path", paths[2]); + EXPECT_EQ("/tmp/more", paths[3]); + EXPECT_EQ("/tmp/even_more", paths[4]); + } +} + // Run multiple times. We want to make sure that static globals don't cause // problems. INSTANTIATE_TEST_CASE_P(ServerRepeat, ServerFixture, ::testing::Range(1, 2)); diff --git a/src/Util.cc b/src/Util.cc index 20fd8fcc85..acdf2ab3ea 100644 --- a/src/Util.cc +++ b/src/Util.cc @@ -19,6 +19,7 @@ #include #endif #include +#include #include "ignition/gazebo/components/Collision.hh" #include "ignition/gazebo/components/Joint.hh" @@ -209,6 +210,100 @@ std::string asFullPath(const std::string &_uri, const std::string &_filePath) // Use platform-specific separator return common::joinPaths(path, uri); } + +////////////////////////////////////////////////// +std::vector resourcePaths() +{ + std::vector gzPaths; + char *gzPathCStr = getenv(kResourcePathEnv.c_str()); + if (gzPathCStr && *gzPathCStr != '\0') + { + gzPaths = common::Split(gzPathCStr, ':'); + } + + gzPaths.erase(std::remove_if(gzPaths.begin(), gzPaths.end(), + [](const std::string &_path) + { + return _path.empty(); + }), gzPaths.end()); + + return gzPaths; +} + +////////////////////////////////////////////////// +void addResourcePaths(const std::vector &_paths) +{ + // SDF paths (for s) + std::vector sdfPaths; + char *sdfPathCStr = getenv(kSdfPathEnv.c_str()); + if (sdfPathCStr && *sdfPathCStr != '\0') + { + sdfPaths = common::Split(sdfPathCStr, ':'); + } + + // Ignition file paths (for s) + auto systemPaths = common::systemPaths(); + std::vector ignPaths; + char *ignPathCStr = getenv(systemPaths->FilePathEnv().c_str()); + if (ignPathCStr && *ignPathCStr != '\0') + { + ignPaths = common::Split(ignPathCStr, ':'); + } + + // Gazebo resource paths + std::vector gzPaths; + char *gzPathCStr = getenv(kResourcePathEnv.c_str()); + if (gzPathCStr && *gzPathCStr != '\0') + { + gzPaths = common::Split(gzPathCStr, ':'); + } + + // Add new paths to gzPaths + for (const auto &path : _paths) + { + if (std::find(gzPaths.begin(), gzPaths.end(), path) == gzPaths.end()) + { + gzPaths.push_back(path); + } + } + + // Append Gz paths to SDF / Ign paths + for (const auto &path : gzPaths) + { + if (std::find(sdfPaths.begin(), sdfPaths.end(), path) == sdfPaths.end()) + { + sdfPaths.push_back(path); + } + + if (std::find(ignPaths.begin(), ignPaths.end(), path) == ignPaths.end()) + { + ignPaths.push_back(path); + } + } + + // Update the vars + std::string sdfPathsStr; + for (const auto &path : sdfPaths) + sdfPathsStr += ':' + path; + + setenv(kSdfPathEnv.c_str(), sdfPathsStr.c_str(), 1); + + std::string ignPathsStr; + for (const auto &path : ignPaths) + ignPathsStr += ':' + path; + + setenv(systemPaths->FilePathEnv().c_str(), ignPathsStr.c_str(), 1); + + std::string gzPathsStr; + for (const auto &path : gzPaths) + gzPathsStr += ':' + path; + + setenv(kResourcePathEnv.c_str(), gzPathsStr.c_str(), 1); + + // Force re-evaluation + // SDF is evaluated at find call + systemPaths->SetFilePathEnv(systemPaths->FilePathEnv()); +} } } } diff --git a/src/cmd/cmdgazebo.rb.in b/src/cmd/cmdgazebo.rb.in index bef801d9b2..1f1c67addb 100755 --- a/src/cmd/cmdgazebo.rb.in +++ b/src/cmd/cmdgazebo.rb.in @@ -114,7 +114,7 @@ COMMANDS = { 'gazebo' => COMMON_OPTIONS + "\n\n" + "Environment variables: \n"\ " IGN_GAZEBO_RESOURCE_PATH Colon separated paths used to locate \n"\ - " resources. Can be useful with the -f option to find an SDF file. \n\n"\ + " resources such as worlds and models. \n\n"\ " IGN_GAZEBO_SYSTEM_PLUGIN_PATH Colon separated paths used to \n"\ " locate system plugins. \n\n"\ " IGN_GUI_PLUGIN_PATH Colon separated paths used to locate GUI \n"\ diff --git a/src/gui/CMakeLists.txt b/src/gui/CMakeLists.txt index b52ada3323..9e311ea071 100644 --- a/src/gui/CMakeLists.txt +++ b/src/gui/CMakeLists.txt @@ -2,6 +2,7 @@ set (gui_sources Gui.cc GuiFileHandler.cc GuiRunner.cc + PathManager.cc TmpIface.cc ) @@ -44,3 +45,22 @@ set(CMAKE_AUTORCC OFF) install(TARGETS ${gui_target} DESTINATION ${IGN_LIB_INSTALL_DIR}) install (FILES gui.config DESTINATION ${IGN_DATA_INSTALL_DIR}/gui) + +# Tests +set (gtest_sources + ${gtest_sources} + Gui_TEST.cc +) +include_directories(${PROJECT_SOURCE_DIR}/test) + +ign_build_tests(TYPE UNIT + SOURCES + ${gtest_sources} + LIB_DEPS + ${PROJECT_LIBRARY_TARGET_NAME} + ${gui_target} + ${EXTRA_TEST_LIB_DEPS} + ignition-gazebo${PROJECT_VERSION_MAJOR} + ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER} + ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} +) diff --git a/src/gui/Gui.cc b/src/gui/Gui.cc index 3221086268..c4a998f74b 100644 --- a/src/gui/Gui.cc +++ b/src/gui/Gui.cc @@ -29,6 +29,7 @@ #include "ignition/gazebo/gui/Gui.hh" #include "GuiFileHandler.hh" +#include "PathManager.hh" namespace ignition { @@ -39,6 +40,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { namespace gui { +////////////////////////////////////////////////// std::unique_ptr createGui( int &_argc, char **_argv, const char *_guiConfig, const char *_defaultGuiConfig, bool _loadPluginsFromSdf) @@ -64,6 +66,9 @@ std::unique_ptr createGui( auto guiFileHandler = new ignition::gazebo::gui::GuiFileHandler(); guiFileHandler->setParent(app->Engine()); + auto pathManager = new ignition::gazebo::gui::PathManager(); + pathManager->setParent(app->Engine()); + // add import path so we can load custom modules app->Engine()->addImportPath(IGN_GAZEBO_GUI_PLUGIN_INSTALL_DIR); @@ -113,7 +118,6 @@ std::unique_ptr createGui( // Get list of worlds ignition::transport::Node node; - bool executed{false}; bool result{false}; unsigned int timeout{5000}; @@ -255,6 +259,7 @@ std::unique_ptr createGui( return nullptr; } } + return app; } diff --git a/src/gui/Gui_TEST.cc b/src/gui/Gui_TEST.cc new file mode 100644 index 0000000000..5cd8176d02 --- /dev/null +++ b/src/gui/Gui_TEST.cc @@ -0,0 +1,159 @@ +/* + * Copyright (C) 2020 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 +#include +#include + +#include "ignition/gazebo/gui/Gui.hh" +#include "ignition/gazebo/test_config.hh" + +int g_argc = 1; +char **g_argv = new char *[g_argc]; + +using namespace ignition; +using namespace gazebo; + +///////////////////////////////////////////////// +TEST(GuiTest, PathManager) +{ + common::Console::SetVerbosity(4); + igndbg << "Start test" << std::endl; + + setenv("IGN_GAZEBO_RESOURCE_PATH", + "/from_env:/tmp/more_env", 1); + setenv("SDF_PATH", "", 1); + setenv("IGN_FILE_PATH", "", 1); + igndbg << "Environment set" << std::endl; + + transport::Node node; + + // Worlds callback + bool worldsCalled{false}; + std::function worldsCb = + [&worldsCalled](msgs::StringMsg_V &_res) + { + _res.add_data("world_name"); + worldsCalled = true; + return true; + }; + node.Advertise("/gazebo/worlds", worldsCb); + igndbg << "Worlds advertised" << std::endl; + + // GUI info callback + bool guiInfoCalled{false}; + std::function guiInfoCb = + [&guiInfoCalled](msgs::GUI &) + { + guiInfoCalled = true; + return true; + }; + node.Advertise("/world/world_name/gui/info", guiInfoCb); + igndbg << "GUI info advertised" << std::endl; + + // Resource paths callback + bool pathsCalled{false}; + std::function pathsCb = + [&pathsCalled](msgs::StringMsg_V &_res) + { + _res.add_data("/from_callback"); + pathsCalled = true; + return true; + }; + node.Advertise("/gazebo/resource_paths/get", pathsCb); + igndbg << "Paths advertised" << std::endl; + + auto app = ignition::gazebo::gui::createGui(g_argc, g_argv, nullptr); + EXPECT_NE(nullptr, app); + igndbg << "GUI created" << std::endl; + + EXPECT_TRUE(worldsCalled); + EXPECT_TRUE(guiInfoCalled); + EXPECT_TRUE(pathsCalled); + + // Check paths + for (auto env : {"IGN_GAZEBO_RESOURCE_PATH", "SDF_PATH", "IGN_FILE_PATH"}) + { + igndbg << "Checking variable [" << env << "]" << std::endl; + char *pathCStr = getenv(env); + + auto paths = common::Split(pathCStr, ':'); + paths.erase(std::remove_if(paths.begin(), paths.end(), + [](std::string const &_path) + { + return _path.empty(); + }), + paths.end()); + + ASSERT_EQ(3u, paths.size()); + EXPECT_EQ("/from_env", paths[0]); + EXPECT_EQ("/tmp/more_env", paths[1]); + EXPECT_EQ("/from_callback", paths[2]); + } + + // Create a subscriber just so we can check when the message has propagated + bool topicCalled{false}; + std::function topicCb = + [&topicCalled](const msgs::StringMsg_V &) + { + topicCalled = true; + }; + node.Subscribe("/gazebo/resource_paths", topicCb); + igndbg << "Paths subscribed" << std::endl; + + // Notify new path through a topic + msgs::StringMsg_V msg; + msg.add_data("/new/path"); + + auto pathPub = node.Advertise("/gazebo/resource_paths"); + pathPub.Publish(msg); + + int sleep{0}; + int maxSleep{30}; + while (!topicCalled && sleep < maxSleep) + { + IGN_SLEEP_MS(100); + sleep++; + } + EXPECT_TRUE(topicCalled); + + // Check paths + for (auto env : {"IGN_GAZEBO_RESOURCE_PATH", "SDF_PATH", "IGN_FILE_PATH"}) + { + igndbg << "Checking variable [" << env << "]" << std::endl; + char *pathCStr = getenv(env); + + auto paths = common::Split(pathCStr, ':'); + paths.erase(std::remove_if(paths.begin(), paths.end(), + [](std::string const &_path) + { + return _path.empty(); + }), + paths.end()); + + ASSERT_EQ(4u, paths.size()); + EXPECT_EQ("/from_env", paths[0]); + EXPECT_EQ("/tmp/more_env", paths[1]); + EXPECT_EQ("/from_callback", paths[2]); + EXPECT_EQ("/new/path", paths[3]); + } +} + diff --git a/src/gui/PathManager.cc b/src/gui/PathManager.cc new file mode 100644 index 0000000000..a55c6cf5cb --- /dev/null +++ b/src/gui/PathManager.cc @@ -0,0 +1,60 @@ +/* + * Copyright (C) 2020 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 +#include + +#include "ignition/gazebo/Util.hh" +#include "PathManager.hh" + +using namespace ignition; +using namespace gazebo; +using namespace gazebo::gui; + +////////////////////////////////////////////////// +void onAddResourcePaths(const msgs::StringMsg_V &_msg) +{ + std::vector paths; + for (auto i = 0; i < _msg.data().size(); ++i) + { + paths.push_back(_msg.data(i)); + } + + addResourcePaths(paths); +} + +///////////////////////////////////////////////// +PathManager::PathManager() +{ + // Get resource paths + std::string service{"/gazebo/resource_paths/get"}; + msgs::StringMsg_V res; + bool result{false}; + auto executed = this->node.Request(service, 5000, res, result); + + if (!executed) + ignerr << "Service call timed out for [" << service << "]" << std::endl; + else if (!result) + ignerr << "Service call failed for [" << service << "]" << std::endl; + + onAddResourcePaths(res); + + this->node.Subscribe("/gazebo/resource_paths", onAddResourcePaths); +} diff --git a/src/gui/PathManager.hh b/src/gui/PathManager.hh new file mode 100644 index 0000000000..05eb7f1ce1 --- /dev/null +++ b/src/gui/PathManager.hh @@ -0,0 +1,51 @@ +/* + * Copyright (C) 2020 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_GUI_PATHMANAGER_HH_ +#define IGNITION_GAZEBO_GUI_PATHMANAGER_HH_ + +#include + +#include + +#include "ignition/gazebo/Export.hh" + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace gui +{ +/// \brief Class for handling paths and their environment variables. +/// It queries the server for paths at startup, and keeps paths updated +/// whenever they change in the server. +class IGNITION_GAZEBO_VISIBLE PathManager : public QObject +{ + Q_OBJECT + + /// \brief Constructor + public: PathManager(); + + /// \brief Transport node. + private: transport::Node node; +}; +} +} +} +} +#endif diff --git a/src/main.cc b/src/main.cc index ef89251c01..9dacc568fb 100644 --- a/src/main.cc +++ b/src/main.cc @@ -117,7 +117,7 @@ void help() << std::endl << "Environment variables:" << std::endl << " IGN_GAZEBO_RESOURCE_PATH Colon separated paths used to locate " - << " resources. Can be useful with the -f option to find an SDF file." + << " resources such as worlds and models." << std::endl << " IGN_GAZEBO_NETWORK_ROLE Participant role used in a distributed " << " simulation environment. Role is one of [PRIMARY, SECONDARY]. This will" diff --git a/src/systems/physics/Physics.cc b/src/systems/physics/Physics.cc index 5b787502a4..7d5cea70a7 100644 --- a/src/systems/physics/Physics.cc +++ b/src/systems/physics/Physics.cc @@ -646,7 +646,7 @@ void PhysicsPrivate::CreatePhysicsEntities(const EntityComponentManager &_ecm) _ecm.EachNew( - [&](const Entity & _entity, + [&](const Entity &_entity, const components::Collision *, const components::Name *_name, const components::Pose *_pose, diff --git a/test/worlds/models/scheme_resource_uri/meshes/box.dae b/test/worlds/models/scheme_resource_uri/meshes/box.dae new file mode 100644 index 0000000000..75b5742f3d --- /dev/null +++ b/test/worlds/models/scheme_resource_uri/meshes/box.dae @@ -0,0 +1,108 @@ + + + + + Blender User + Blender 2.74.0 commit date:2015-03-31, commit time:13:39, hash:000dfc0 + + 2015-05-26T11:01:50 + 2015-05-26T11:01:50 + + Z_UP + + + + + + + + 0.2 0.2 0.2 1 + + + 0.9 0.9 0.9 1 + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + 1 1 -1 1 -1 -1 -1 -0.9999998 -1 -0.9999997 1 -1 1 0.9999995 1 0.9999994 -1.000001 1 -1 -0.9999997 1 -1 1 1 + + + + + + + + + + 0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.08616e-7 -1.19209e-7 2.08616e-7 1 1.78814e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 -1.49012e-7 2.68221e-7 1 2.38419e-7 + + + + + + + + + + 0.004854381 0.6715211 0.3284789 0.671521 0.3284789 0.9951456 0.9951456 0.6618123 0.6715211 0.6618123 0.6715211 0.3381878 0.00485444 0.6618123 0.004854321 0.3381878 0.3284789 0.3381878 0.004854321 0.00485444 0.3284789 0.004854321 0.3284789 0.3284789 0.9951457 0.3284789 0.6715211 0.3284789 0.6715211 0.00485444 0.6618123 0.004854381 0.6618123 0.3284788 0.3381878 0.3284789 0.004854321 0.9951456 0.004854381 0.6715211 0.3284789 0.9951456 0.9951456 0.3381877 0.9951456 0.6618123 0.6715211 0.3381878 0.3284791 0.6618123 0.00485444 0.6618123 0.3284789 0.3381878 0.004854381 0.328479 0.004854321 0.00485444 0.3284789 0.3284789 0.9951457 0.004854321 0.9951457 0.3284789 0.6715211 0.00485444 0.3381877 0.004854321 0.6618123 0.004854381 0.3381878 0.3284789 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35

+
+
+
+
+ + + + + 0.3999998 0 0 0 0 0.4 0 0 0 0 0.4 0 0 0 0 1 + + + + + + + + + + + + + + + +
diff --git a/test/worlds/models/scheme_resource_uri/model.config b/test/worlds/models/scheme_resource_uri/model.config new file mode 100644 index 0000000000..fd4cb55a64 --- /dev/null +++ b/test/worlds/models/scheme_resource_uri/model.config @@ -0,0 +1,7 @@ + + + scheme_resource_uri + 1.0 + model.sdf + + diff --git a/test/worlds/models/scheme_resource_uri/model.sdf b/test/worlds/models/scheme_resource_uri/model.sdf new file mode 100644 index 0000000000..a1f122416e --- /dev/null +++ b/test/worlds/models/scheme_resource_uri/model.sdf @@ -0,0 +1,25 @@ + + + + + 0 0 1 0 0 0 + + + + + model://scheme_resource_uri/meshes/box.dae + + + + + + + model://scheme_resource_uri/meshes/box.dae + + + + + + + diff --git a/test/worlds/resource_paths.sdf b/test/worlds/resource_paths.sdf new file mode 100644 index 0000000000..ff5c5910f4 --- /dev/null +++ b/test/worlds/resource_paths.sdf @@ -0,0 +1,13 @@ + + + + + + + + model://scheme_resource_uri + + + diff --git a/tutorials/resources.md b/tutorials/resources.md new file mode 100644 index 0000000000..5de32c97a9 --- /dev/null +++ b/tutorials/resources.md @@ -0,0 +1,158 @@ +\page resources Finding resources + +Setting up and running a simulation can involve loading various kinds of +resources, such as robot models and plugins, from different locations, which +can include a local filesystem and online servers. Ignition Gazebo offers +a few different mechanisms for locating required resources. + +## Plugins + +A plugin is a shared library that adheres to a specific API and is loaded at +runtime. Typically, plugins are scoped to perform a narrow set of features. +For example, the `diff_drive` plugin, provided by Ignition Gazebo, implements +a differential drive controller for mobile robots. + +Ignition relies on plugins for rendering, physics simulation, sensor data +generation, and many of the capabilities. The following sections describe +how Ignition finds and loads different types of plugins. + +### System Plugins + +A system plugin is used by Ignition Gazebo, and provides an entry point for +simulation customization and control. Refer to the \subpage createsystemplugins +tutorial for information about creating your own system plugin. + +System plugins may be loaded through: + +* Tags in SDF files, where `filename` is the shared library and + `name` is the class to be loaded. A system plugin can be attached to + different entities. + * Attached to the **world**: `` + * Attached to a **model**: `` + * Attached to a **sensor**: `` +* Passing the shared library and class to be loaded through + [PluginInfo](https://ignitionrobotics.org/api/gazebo/3.0/classignition_1_1gazebo_1_1ServerConfig_1_1PluginInfo.html) + (within [ServerConfig](https://ignitionrobotics.org/api/gazebo/3.0/classignition_1_1gazebo_1_1ServerConfig.html)) + when instantiating the + [Server](https://ignitionrobotics.org/api/gazebo/3.0/classignition_1_1gazebo_1_1Server.html#a084ef7616f5af42061a7aeded5651ab0). + +Ignition will look for system plugins on the following paths, in order: + +1. All paths on the `IGN_GAZEBO_SYSTEM_PLUGIN_PATH` environment variable +2. `$HOME/.ignition/gazebo/plugins` +3. [Systems that are installed with Ignition Gazebo](https://github.com/ignitionrobotics/ign-gazebo/blob/master/src/systems/) + +### Ignition GUI plugins + +Each [Ignition GUI](https://ignitionrobotics.org/libs/rendering) plugin +defines a widget. + +GUI plugins may be loaded through: + +* Tags in SDF world files, where `filename` is the shared library: + * `` +* Tags in [GUI config files](https://ignitionrobotics.org/api/gui/3.0/config.html), + where `filename` is the shared library: + * `` +* The plugin menu on the top-right of the screen. + +Ignition will look for GUI plugins on the following paths, in order: + +1. All paths set on the `IGN_GUI_PLUGIN_PATH` environment variable +2. [GUI plugins that are installed with Ignition Gazebo](https://github.com/ignitionrobotics/ign-gazebo/tree/master/src/gui/plugins) +3. Other paths added by calling `ignition::gui::App()->AddPluginPath` +4. `~/.ignition/gui/plugins` +5. [Plugins which are installed with Ignition GUI](https://ignitionrobotics.org/api/gui/3.0/namespaceignition_1_1gui_1_1plugins.html) + +### Physics engines + +[Ignition Physics](https://ignitionrobotics.org/libs/physics) +uses a plugin architecture and its physics engines are +built as plugins that are loaded at run time using +[Ignition Plugin](https://ignitionrobotics.org/libs/plugin). + +See the [Physics engines](physics.html) +tutorial for more details. + +### Rendering engines + +[Ignition Rendering](https://ignitionrobotics.org/libs/rendering) +uses a plugin architecture and its render engines are +built as plugins that are loaded at run time using +[Ignition Plugin](https://ignitionrobotics.org/libs/plugin). + +At the moment, Ignition Rendering will only look for render engine plugin +shared libraries installed within its `/lib` directory. +Likewise, the resources used by these engines are located in Ignition +Rendering's `/share` directory. + +### Sensors + +Each unique type of sensor in +[Ignition Sensors](https://ignitionrobotics.org/libs/sensors) is a plugin. When +a particular sensor type is requested, the relevant plugin is loaded by +[Ignition Plugin](https://ignitionrobotics.org/libs/plugin) and a +sensor object is instantiated from it. + +At the moment, Ignition Sensors will only look for sensor plugin +shared libraries installed within its `/lib` directory. + +## Models, lights, actors + +Top-level entities such as models, lights and actors may be loaded through: + +* Tags in SDF world files: + * `` + * `` + * `` + * `` (path / URL) +* The `/world//create` service: + * SDF file as string (`` / `` / `` root) + * Path / URL to SDF file + * (TODO) `ignition::msgs::Model`, `ignition::msgs::Light` +* Within a system, using + [SdfEntityCreator](https://ignitionrobotics.org/api/gazebo/3.0/classignition_1_1gazebo_1_1SdfEntityCreator.html) + or directly creating components and entities. + +Ignition will look for URIs (path / URL) in the following, in order: + +1. All paths on the `IGN_GAZEBO_RESOURCE_PATH`\* environment variable (if + path is URI, scheme is stripped) +2. Current running path / absolute path +3. [Ignition Fuel](https://app.ignitionrobotics.org/fuel/models) + 1. Cache (i.e. `$HOME/.ignition/fuel`) + 2. Web server + +> \* The `SDF_PATH` environment variable also works in some scenarios, but + it's not recommended when using Ignition Gazebo. + +## Meshes + +Mesh files may be loaded through: + +* Tags in SDF files: + * `` + * `` + * `` + +Ignition will look for URIs (path / URL) in the following, in order: + +1. Current running path / absolute path +2. All paths on the `IGN_GAZEBO_RESOURCE_PATH`\* environment variable (if path + is URI, scheme is stripped) + +> \* The `IGN_FILE_PATH` environment variable also works in some scenarios, but + it's not recommended when using Ignition Gazebo. + +### GUI configuration + +Ignition Gazebo's +[GUI configuration](https://ignitionrobotics.org/api/gui/3.0/config.html) +can come from the following, in order: + +1. The command line option `--gui-config ` +2. Plugins within SDF's `` +3. `$HOME/.ignition/gazebo/gui.config` (if that file doesn't +exist, the default `gui.config` file that is installed with Ignition Gazebo +will be copied to that location) +