Skip to content

Commit

Permalink
Convert ignitionrobotics to gazebosim in sources and includes (#1758)
Browse files Browse the repository at this point in the history
Signed-off-by: Nate Koenig <nate@openrobotics.org>

Signed-off-by: Nate Koenig <nate@openrobotics.org>
Co-authored-by: Nate Koenig <nate@openrobotics.org>
  • Loading branch information
nkoenig and Nate Koenig committed Oct 12, 2022
1 parent ac5df7f commit 3276fbd
Show file tree
Hide file tree
Showing 15 changed files with 31 additions and 28 deletions.
3 changes: 1 addition & 2 deletions include/ignition/gazebo/Entity.hh
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,7 @@
#include <ignition/gazebo/config.hh>
#include <ignition/gazebo/Export.hh>

/// \brief This library is part of the [Ignition
/// Robotics](https://ignitionrobotics.org) project.
/// \brief This library is part of the [Gazebo](https://gazebosim.org) project.
namespace ignition
{
/// \brief Gazebo is a leading open source robotics simulator, that
Expand Down
4 changes: 2 additions & 2 deletions include/ignition/gazebo/ServerConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -308,14 +308,14 @@ namespace ignition
UpdatePeriod() const;

/// \brief Path to where simulation resources, such as models downloaded
/// from fuel.ignitionrobotics.org, should be stored.
/// from fuel.gazebosim.org, should be stored.
/// \return Path to a location on disk. An empty string indicates that
/// the default value will be used, which is currently
/// ~/.ignition/fuel.
public: const std::string &ResourceCache() const;

/// \brief Set the path to where simulation resources, such as models
/// downloaded from fuel.ignitionrobotics.org, should be stored.
/// downloaded from fuel.gazebosim.org, should be stored.
/// \param[in] _path Path to a location on disk. An empty string
/// indicates that the default value will be used, which is currently
/// ~/.ignition/fuel.
Expand Down
12 changes: 6 additions & 6 deletions src/SdfGenerator_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -544,17 +544,17 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedNotExpanded)
TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris)
{
const std::string goodUri =
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2";
"https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2";

// These are URIs that are potentially problematic.
const std::vector<std::string> fuelUris = {
// Thes following two URIs are valid, but have a trailing '/'
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/",
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/2/",
"https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/",
"https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/2/",
// Thes following two URIs are invalid, and will not be saved
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/"
"https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/"
"notInt",
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack/"
"https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack/"
"notInt/",
};

Expand Down Expand Up @@ -609,7 +609,7 @@ TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithInvalidUris)
TEST_F(ElementUpdateFixture, WorldWithModelsIncludedWithNonFuelUris)
{
const std::vector<std::string> includeUris = {
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Backpack",
"https://fuel.gazebosim.org/1.0/OpenRobotics/models/Backpack",
std::string("file://") + PROJECT_SOURCE_PATH +
"/test/worlds/models/sphere"};

Expand Down
2 changes: 1 addition & 1 deletion src/ServerConfig.cc
Original file line number Diff line number Diff line change
Expand Up @@ -270,7 +270,7 @@ class ignition::gazebo::ServerConfigPrivate
public: std::string logRecordCompressPath = "";

/// \brief Path to where simulation resources, such as models downloaded
/// from fuel.ignitionrobotics.org, should be stored.
/// from fuel.gazebosim.org, should be stored.
public: std::string resourceCache = "";

/// \brief File containing physics engine plugin. If empty, DART will be used.
Expand Down
2 changes: 1 addition & 1 deletion src/Server_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1002,7 +1002,7 @@ TEST_P(ServerFixture, CachedFuelWorld)

ServerConfig serverConfig;
auto fuelWorldURL =
"https://fuel.ignitionrobotics.org/1.0/OpenRobotics/worlds/Test%20world";
"https://fuel.gazebosim.org/1.0/OpenRobotics/worlds/Test%20world";
EXPECT_TRUE(serverConfig.SetSdfFile(fuelWorldURL));

EXPECT_EQ(fuelWorldURL, serverConfig.SdfFile());
Expand Down
8 changes: 4 additions & 4 deletions src/World.cc
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ Entity World::LightByName(const EntityComponentManager &_ecm,
const std::string &_name) const
{
// Can't use components::Light in EntityByComponents, see
// https://github.com/ignitionrobotics/ign-gazebo/issues/376
// https://github.com/gazebosim/gz-sim/issues/376
auto entities = _ecm.EntitiesByComponents(
components::ParentEntity(this->dataPtr->id),
components::Name(_name));
Expand All @@ -128,7 +128,7 @@ Entity World::ActorByName(const EntityComponentManager &_ecm,
const std::string &_name) const
{
// Can't use components::Actor in EntityByComponents, see
// https://github.com/ignitionrobotics/ign-gazebo/issues/376
// https://github.com/gazebosim/gz-sim/issues/376
auto entities = _ecm.EntitiesByComponents(
components::ParentEntity(this->dataPtr->id),
components::Name(_name));
Expand All @@ -155,7 +155,7 @@ Entity World::ModelByName(const EntityComponentManager &_ecm,
std::vector<Entity> World::Lights(const EntityComponentManager &_ecm) const
{
// Can't use components::Light in EntityByComponents, see
// https://github.com/ignitionrobotics/ign-gazebo/issues/376
// https://github.com/gazebosim/gz-sim/issues/376
auto entities = _ecm.EntitiesByComponents(
components::ParentEntity(this->dataPtr->id));

Expand All @@ -172,7 +172,7 @@ std::vector<Entity> World::Lights(const EntityComponentManager &_ecm) const
std::vector<Entity> World::Actors(const EntityComponentManager &_ecm) const
{
// Can't use components::Actor in EntityByComponents, see
// https://github.com/ignitionrobotics/ign-gazebo/issues/376
// https://github.com/gazebosim/gz-sim/issues/376
auto entities = _ecm.EntitiesByComponents(
components::ParentEntity(this->dataPtr->id));

Expand Down
4 changes: 2 additions & 2 deletions src/cmd/cmdgazebo.rb.in
Original file line number Diff line number Diff line change
Expand Up @@ -456,7 +456,7 @@ has properly set the DYLD_LIBRARY_PATH environment variables."

if plugin.end_with? ".dylib"
puts "`ign gazebo` currently only works with the -s argument on macOS.
See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info."
See https://github.com/gazebosim/gz-sim/issues/44 for more info."
exit(-1)
end

Expand Down Expand Up @@ -511,7 +511,7 @@ See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info."
else options['gui']
if plugin.end_with? ".dylib"
puts "`ign gazebo` currently only works with the -s argument on macOS.
See https://github.com/ignitionrobotics/ign-gazebo/issues/44 for more info."
See https://github.com/gazebosim/gz-sim/issues/44 for more info."
exit(-1)
end

Expand Down
8 changes: 4 additions & 4 deletions src/gui/AboutDialogHandler.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,9 @@ AboutDialogHandler::AboutDialogHandler()
"<td style='padding-right: 10px;'>Documentation:"
"</td>"
"<td>"
"<a href='https://ignitionrobotics.org/libs/gazebo' "
"<a href='https://gazebosim.org/libs/sim' "
"style='text-decoration: none; color: #f58113'>"
"https://ignitionrobotics.org/libs/gazebo"
"https://gazebosim.org/libs/sim"
"</a>"
"</td>"
"</tr>"
Expand All @@ -46,9 +46,9 @@ AboutDialogHandler::AboutDialogHandler()
"Tutorials:"
"</td>"
"<td>"
"<a href='https://ignitionrobotics.org/docs/' "
"<a href='https://gazebosim.org/docs/' "
"style='text-decoration: none; color: #f58113'>"
"https://ignitionrobotics.org/docs/"
"https://gazebosim.org/docs/"
"</a>"
"</td>"
"</tr>"
Expand Down
2 changes: 1 addition & 1 deletion src/gui/Gui_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ using namespace ignition;
using namespace ignition::gazebo::gui;

/////////////////////////////////////////////////
// https://github.com/ignitionrobotics/ign-gazebo/issues/8
// https://github.com/gazebosim/gz-sim/issues/8
TEST(GuiTest, IGN_UTILS_TEST_DISABLED_ON_MAC(PathManager))
{
common::Console::SetVerbosity(4);
Expand Down
2 changes: 1 addition & 1 deletion src/gui/plugins/scene3d/Scene3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2203,7 +2203,7 @@ void TextureNode::PrepareNode()
newId, sz, QQuickWindow::TextureIsOpaque);
#else
// TODO(anyone) Use createTextureFromNativeObject
// https://github.com/ignitionrobotics/ign-gui/issues/113
// https://github.com/gazebosim/gz-gui/issues/113
#ifndef _WIN32
# pragma GCC diagnostic push
# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
Expand Down
2 changes: 1 addition & 1 deletion src/ign.hh
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ extern "C" IGNITION_GAZEBO_VISIBLE int runGui(

/// \brief External hook to find or download a fuel world provided a URL.
/// \param[in] _pathToResource Path to the fuel world resource, ie,
/// https://staging-fuel.ignitionrobotics.org/1.0/gmas/worlds/ShapesClone
/// https://staging-fuel.gazebosim.org/1.0/gmas/worlds/ShapesClone
/// \return C-string containing the path to the local world sdf file
extern "C" IGNITION_GAZEBO_VISIBLE const char *findFuelResource(
char *_pathToResource);
Expand Down
4 changes: 4 additions & 0 deletions src/ign_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,10 @@ static const std::string kIgnModelCommand(
/////////////////////////////////////////////////
std::string customExecStr(std::string _cmd)
{
// Augment the system plugin path.
gz::common::setenv("IGN_GAZEBO_SYSTEM_PLUGIN_PATH",
gz::common::joinPaths(std::string(PROJECT_BINARY_PATH), "lib").c_str());

_cmd += " 2>&1";
FILE *pipe = popen(_cmd.c_str(), "r");

Expand Down
2 changes: 1 addition & 1 deletion src/network/NetworkManagerPrimary.cc
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@ bool NetworkManagerPrimary::SecondariesCanStep() const
// TODO(anyone) Ideally we'd check the number of connections against the
// number of expected secondaries, but there's no interface for that
// on ign-transport yet:
// https://github.com/ignitionrobotics/ign-transport/issues/39
// https://github.com/gazebosim/gz-transport/issues/39
return this->simStepPub.HasConnections();
}

Expand Down
2 changes: 1 addition & 1 deletion src/systems/ackermann_steering/AckermannSteering.hh
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ namespace systems
/// right_steering_joint
///
/// References:
/// https://github.com/ignitionrobotics/ign-gazebo/tree/ign-gazebo4/src/systems/diff_drive
/// https://github.com/gazebosim/gz-sim/tree/ign-gazebo4/src/systems/diff_drive
/// https://www.auto.tuwien.ac.at/bib/pdf_TR/TR0183.pdf
/// https://github.com/froohoo/ackermansteer/blob/master/ackermansteer/

Expand Down
2 changes: 1 addition & 1 deletion src/systems/battery_plugin/LinearBatteryPlugin.hh
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ namespace systems
/// - `<charging_time>` Hours taken to fully charge the battery.
/// (Required if `<enable_recharge>` is set to true)
/// - `<fix_issue_225>` True to change the battery behavior to fix some issues
/// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225.
/// described in https://github.com/gazebosim/gz-sim/issues/225.
class LinearBatteryPlugin
: public System,
public ISystemConfigure,
Expand Down

0 comments on commit 3276fbd

Please sign in to comment.