Skip to content

Commit

Permalink
Address merge issues
Browse files Browse the repository at this point in the history
Signed-off-by: Nate Koenig <[email protected]>
  • Loading branch information
Nate Koenig committed Nov 15, 2022
1 parent 878625d commit 78b6699
Show file tree
Hide file tree
Showing 8 changed files with 1,042 additions and 1,052 deletions.
2,056 changes: 1,029 additions & 1,027 deletions Changelog.md

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
Expand Up @@ -291,7 +291,7 @@ void JointPositionController::Update(const UpdateInfo &,
QMetaObject::invokeMethod(&this->dataPtr->jointsModel,
"RemoveJoint",
Qt::QueuedConnection,
Q_ARG(gz:sim::Entity, jointEntity));
Q_ARG(sim::Entity, jointEntity));
}
}
}
Expand Down
6 changes: 0 additions & 6 deletions src/gui/plugins/scene_manager/GzSceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -132,12 +132,6 @@ void GzSceneManager::Update(const UpdateInfo &_info,
this->dataPtr->renderEnginePluginPathsInit = true;
}

if (!this->dataPtr->renderEnginePluginPathsInit)
{
this->dataPtr->renderUtil.InitRenderEnginePluginPaths();
this->dataPtr->renderEnginePluginPathsInit = true;
}

this->dataPtr->renderUtil.UpdateECM(_info, _ecm);

std::lock_guard<std::mutex> lock(this->dataPtr->newRemovedEntityMutex);
Expand Down
4 changes: 1 addition & 3 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -168,7 +168,6 @@ class gz::sim::systems::PhysicsPrivate
physics::LinkFrameSemantics,
physics::ForwardStep,
physics::RemoveModelFromWorld,
physics::sdf::ConstructSdfLink,
physics::sdf::ConstructSdfModel,
physics::sdf::ConstructSdfWorld,
physics::GetLinkFromModel,
Expand Down Expand Up @@ -470,8 +469,7 @@ class gz::sim::systems::PhysicsPrivate
physics::GetJointFromModel,
physics::GetBasicJointProperties,
physics::GetBasicJointState,
physics::SetBasicJointState,
physics::sdf::ConstructSdfJoint>{};
physics::SetBasicJointState>{};

/// \brief Feature list to construct joints
public: struct ConstructSdfJointFeatureList : gz::physics::FeatureList<
Expand Down
14 changes: 7 additions & 7 deletions test/integration/level_manager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test>
{
InternalFixture::SetUp();

ignition::gazebo::ServerConfig serverConfig;
sim::ServerConfig serverConfig;

// Except tile_0, which is on the default level, every tile belongs to a
// level. The name of the level corresponds to the tile in its suffix, i.e.,
Expand All @@ -116,12 +116,12 @@ class LevelManagerFixture : public InternalFixture<::testing::Test>
serverConfig.SetUseLevels(true);

EXPECT_EQ(nullptr, this->server);
this->server = std::make_unique<gazebo::Server>(serverConfig);
this->server = std::make_unique<sim::Server>(serverConfig);

test::Relay testSystem;
// Check entities loaded on the default level
testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &,
const gazebo::EntityComponentManager &_ecm)
testSystem.OnPostUpdate([&](const sim::UpdateInfo &,
const sim::EntityComponentManager &_ecm)
{
_ecm.Each<components::Model, components::Name>(
[&](const Entity &, const components::Model *,
Expand Down Expand Up @@ -170,7 +170,7 @@ class LevelManagerFixture : public InternalFixture<::testing::Test>
this->server->Run(true, 1, false);
}

public: std::unique_ptr<gazebo::Server> server;
public: std::unique_ptr<sim::Server> server;
public: std::vector<std::string> loadedModels;
public: std::vector<std::string> unloadedModels;
public: std::vector<std::string> loadedLights;
Expand All @@ -187,8 +187,8 @@ TEST_F(LevelManagerFixture, GZ_UTILS_TEST_ENABLED_ONLY_ON_LINUX(DefaultLevel))

test::Relay recorder;
// Check entities loaded on the default level
recorder.OnPostUpdate([&](const gazebo::UpdateInfo &,
const gazebo::EntityComponentManager &_ecm)
recorder.OnPostUpdate([&](const sim::UpdateInfo &,
const sim::EntityComponentManager &_ecm)
{
_ecm.Each<components::DefaultLevel, components::LevelEntityNames>(
[&](const Entity &, const components::DefaultLevel *,
Expand Down
2 changes: 1 addition & 1 deletion test/integration/sdf_include.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,6 @@ TEST_F(SdfInclude, GZ_UTILS_TEST_DISABLED_ON_WIN32(DownloadFromFuel))
Server server(serverConfig);

EXPECT_TRUE(common::exists(path +
"/fuel.ignitionrobotics.org/openrobotics/models/ground plane" +
"/fuel.gazebosim.org/openrobotics/models/ground plane" +
"/1/model.sdf"));
}
8 changes: 2 additions & 6 deletions test/worlds/diff_drive_no_plugin.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,8 @@
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>

<light type="directional" name="sun">
Expand Down
2 changes: 1 addition & 1 deletion test/worlds/include.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
</physics>

<include>
<uri>https://fuel.gazebosim.org/1.0/OpenRobotics/models/ground plane/1</uri>
<uri>https://fuel.gazebosim.org/1.0/openrobotics/models/ground plane/1</uri>
</include>
</world>
</sdf>

0 comments on commit 78b6699

Please sign in to comment.