Skip to content

Commit

Permalink
Fix deprecation warnings (#572)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina authored Jan 20, 2021
1 parent d3ef3c2 commit 694e248
Show file tree
Hide file tree
Showing 8 changed files with 51 additions and 51 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ set(IGN_MSGS_VER ${ignition-msgs7_VERSION_MAJOR})
#--------------------------------------
# Find ignition-common
# Always use the profiler component to get the headers, regardless of status.
ign_find_package(ignition-common3 VERSION 3.5
ign_find_package(ignition-common3 VERSION 3.6
COMPONENTS
profiler
events
Expand Down
3 changes: 3 additions & 0 deletions include/ignition/gazebo/detail/EntityComponentManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,8 @@ namespace ignition
{
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
//////////////////////////////////////////////////
namespace traits
{
Expand Down Expand Up @@ -547,5 +549,6 @@ bool EntityComponentManager::RemoveComponent(Entity _entity)
}
}
}
}

#endif
4 changes: 2 additions & 2 deletions src/gui/plugins/scene3d/Scene3D.cc
Original file line number Diff line number Diff line change
Expand Up @@ -702,15 +702,15 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf)
// Terminate any pre-existing spawned entities
this->TerminateSpawnPreview();

if (!_sdf.ModelCount())
if (nullptr == _sdf.Model())
{
ignwarn << "Only model entities can be spawned at the moment." << std::endl;
this->TerminateSpawnPreview();
return false;
}

// Only preview first model
sdf::Model model = *(_sdf.ModelByIndex(0));
sdf::Model model = *(_sdf.Model());
this->dataPtr->spawnPreviewPose = model.RawPose();
model.SetName(ignition::common::Uuid().String());
Entity modelId = this->UniqueId();
Expand Down
4 changes: 2 additions & 2 deletions src/network/NetworkManagerPrimary.cc
Original file line number Diff line number Diff line change
Expand Up @@ -265,9 +265,9 @@ void NetworkManagerPrimary::PopulateAffinities(
{
auto secondaryIt = this->secondaries.begin();

for (const auto &[level, performers] : lToPNew)
for (const auto &it : lToPNew)
{
for (const auto &performer : performers)
for (const auto &performer : it.second)
{
this->SetAffinity(performer, secondaryIt->second->prefix,
_msg.add_affinity());
Expand Down
8 changes: 4 additions & 4 deletions src/systems/breadcrumbs/Breadcrumbs.cc
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ void Breadcrumbs::Configure(const Entity &_entity,
}
return;
}
if (this->modelRoot.ModelCount() == 0)
if (nullptr == this->modelRoot.Model())
{
ignerr << "Model not found in <breadcrumb>" << std::endl;
return;
Expand All @@ -133,7 +133,7 @@ void Breadcrumbs::Configure(const Entity &_entity,

// Subscribe to commands
std::string topic{"/model/" + this->model.Name(_ecm) + "/breadcrumbs/" +
this->modelRoot.ModelByIndex(0)->Name() + "/deploy"};
this->modelRoot.Model()->Name() + "/deploy"};

if (_sdf->HasElement("topic"))
topic = _sdf->Get<std::string>("topic");
Expand Down Expand Up @@ -183,7 +183,7 @@ void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
if (this->maxDeployments < 0 ||
this->numDeployments < this->maxDeployments)
{
sdf::Model modelToSpawn = *this->modelRoot.ModelByIndex(0);
sdf::Model modelToSpawn = *this->modelRoot.Model();
std::string desiredName =
modelToSpawn.Name() + "_" + std::to_string(this->numDeployments);

Expand Down Expand Up @@ -257,7 +257,7 @@ void Breadcrumbs::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
}
else
{
ignmsg << "Asked to deploy " << this->modelRoot.ModelByIndex(0)->Name()
ignmsg << "Asked to deploy " << this->modelRoot.Model()->Name()
<< " but the maximum number of deployments has reached the "
<< "limit of " << this->maxDeployments << std::endl;
}
Expand Down
57 changes: 27 additions & 30 deletions src/systems/log/LogRecord.cc
Original file line number Diff line number Diff line change
Expand Up @@ -538,44 +538,41 @@ bool LogRecordPrivate::SaveModels(const std::set<std::string> &_models)

// Look for URIs in SDF and convert them to paths relative to the model
// directory
for (uint64_t mi = 0; mi < root.ModelCount(); mi++)
const sdf::Model *model = root.Model();
for (uint64_t li = 0; li < model->LinkCount(); li++)
{
const sdf::Model *model = root.ModelByIndex(mi);
for (uint64_t li = 0; li < model->LinkCount(); li++)
const sdf::Link *link = model->LinkByIndex(li);
for (uint64_t ci = 0; ci < link->CollisionCount(); ci++)
{
const sdf::Link *link = model->LinkByIndex(li);
for (uint64_t ci = 0; ci < link->CollisionCount(); ci++)
const sdf::Collision *collision = link->CollisionByIndex(ci);
const sdf::Geometry *geometry = collision->Geom();
const sdf::Mesh *mesh = geometry->MeshShape();
if (mesh != nullptr)
{
const sdf::Collision *collision = link->CollisionByIndex(ci);
const sdf::Geometry *geometry = collision->Geom();
const sdf::Mesh *mesh = geometry->MeshShape();
if (mesh != nullptr)
// Replace path with relative path
std::string relPath = convertToRelativePath(mesh->Uri(), srcPath);
sdf::ElementPtr meshElem = mesh->Element();
if (meshElem->HasElement("uri"))
{
// Replace path with relative path
std::string relPath = convertToRelativePath(mesh->Uri(), srcPath);
sdf::ElementPtr meshElem = mesh->Element();
if (meshElem->HasElement("uri"))
{
sdf::ElementPtr uriElem = meshElem->GetElement("uri");
uriElem->Set(relPath);
}
sdf::ElementPtr uriElem = meshElem->GetElement("uri");
uriElem->Set(relPath);
}
}
for (uint64_t vi = 0; vi < link->VisualCount(); vi++)
}
for (uint64_t vi = 0; vi < link->VisualCount(); vi++)
{
const sdf::Visual *visual = link->VisualByIndex(vi);
const sdf::Geometry *geometry = visual->Geom();
const sdf::Mesh *mesh = geometry->MeshShape();
if (mesh != nullptr)
{
const sdf::Visual *visual = link->VisualByIndex(vi);
const sdf::Geometry *geometry = visual->Geom();
const sdf::Mesh *mesh = geometry->MeshShape();
if (mesh != nullptr)
// Replace path with relative path
std::string relPath = convertToRelativePath(mesh->Uri(), srcPath);
sdf::ElementPtr meshElem = mesh->Element();
if (meshElem->HasElement("uri"))
{
// Replace path with relative path
std::string relPath = convertToRelativePath(mesh->Uri(), srcPath);
sdf::ElementPtr meshElem = mesh->Element();
if (meshElem->HasElement("uri"))
{
sdf::ElementPtr uriElem = meshElem->GetElement("uri");
uriElem->Set(relPath);
}
sdf::ElementPtr uriElem = meshElem->GetElement("uri");
uriElem->Set(relPath);
}
}
}
Expand Down
20 changes: 10 additions & 10 deletions src/systems/user_commands/UserCommands.cc
Original file line number Diff line number Diff line change
Expand Up @@ -441,15 +441,15 @@ bool CreateCommand::Execute()
bool isModel{false};
bool isLight{false};
bool isActor{false};
if (root.ModelCount() > 0)
if (nullptr != root.Model())
{
isModel = true;
}
else if (root.LightCount() > 0)
else if (nullptr != root.Light())
{
isLight = true;
}
else if (root.ActorCount() > 0)
else if (nullptr != root.Actor())
{
isActor = true;
}
Expand All @@ -460,7 +460,7 @@ bool CreateCommand::Execute()
return false;
}

if ((root.ModelCount() + root.LightCount() + root.ActorCount()) > 1)
if ((isModel && isLight) || (isModel && isActor) || (isLight && isActor))
{
ignwarn << "Expected exactly one top-level <model>, <light> or <actor>, "
<< "but found more. Only the 1st will be spawned." << std::endl;
Expand All @@ -474,15 +474,15 @@ bool CreateCommand::Execute()
}
else if (isModel)
{
desiredName = root.ModelByIndex(0)->Name();
desiredName = root.Model()->Name();
}
else if (isLight)
{
desiredName = root.LightByIndex(0)->Name();
desiredName = root.Light()->Name();
}
else if (isActor)
{
desiredName = root.ActorByIndex(0)->Name();
desiredName = root.Actor()->Name();
}

// Check if there's already a top-level entity with the given name
Expand Down Expand Up @@ -514,19 +514,19 @@ bool CreateCommand::Execute()
Entity entity{kNullEntity};
if (isModel)
{
auto model = *root.ModelByIndex(0);
auto model = *root.Model();
model.SetName(desiredName);
entity = this->iface->creator->CreateEntities(&model);
}
else if (isLight)
{
auto light = root.LightByIndex(0);
auto light = root.Light();
light->SetName(desiredName);
entity = this->iface->creator->CreateEntities(light);
}
else if (isActor)
{
auto actor = *root.ActorByIndex(0);
auto actor = *root.Actor();
actor.SetName(desiredName);
entity = this->iface->creator->CreateEntities(&actor);
}
Expand Down
4 changes: 2 additions & 2 deletions test/integration/sdf_frame_semantics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -87,9 +87,9 @@ class SdfFrameSemanticsTest : public ::testing::Test
sdf::Root root;
sdf::Errors errors = root.LoadSdfString(_sdfString);
EXPECT_TRUE(errors.empty());
ASSERT_EQ(root.ModelCount(), 1u);
ASSERT_NE(nullptr, root.Model());

Entity modelEntity = this->creator->CreateEntities(root.ModelByIndex(0));
Entity modelEntity = this->creator->CreateEntities(root.Model());
Entity worldEntity = this->ecm->EntityByComponents(components::World());
this->creator->SetParent(modelEntity, worldEntity);
}
Expand Down

0 comments on commit 694e248

Please sign in to comment.