diff --git a/CMakeLists.txt b/CMakeLists.txt index 977a4f0f8b..c22e8b812d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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 diff --git a/include/ignition/gazebo/detail/EntityComponentManager.hh b/include/ignition/gazebo/detail/EntityComponentManager.hh index 027baf355c..880dba745c 100644 --- a/include/ignition/gazebo/detail/EntityComponentManager.hh +++ b/include/ignition/gazebo/detail/EntityComponentManager.hh @@ -32,6 +32,8 @@ namespace ignition { namespace gazebo { +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { ////////////////////////////////////////////////// namespace traits { @@ -547,5 +549,6 @@ bool EntityComponentManager::RemoveComponent(Entity _entity) } } } +} #endif diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 902cde39c3..63c36f291c 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -702,7 +702,7 @@ 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(); @@ -710,7 +710,7 @@ bool IgnRenderer::GeneratePreview(const sdf::Root &_sdf) } // 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(); diff --git a/src/network/NetworkManagerPrimary.cc b/src/network/NetworkManagerPrimary.cc index 84542b711c..e9759eb735 100644 --- a/src/network/NetworkManagerPrimary.cc +++ b/src/network/NetworkManagerPrimary.cc @@ -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()); diff --git a/src/systems/breadcrumbs/Breadcrumbs.cc b/src/systems/breadcrumbs/Breadcrumbs.cc index a06789d845..8813b807ff 100644 --- a/src/systems/breadcrumbs/Breadcrumbs.cc +++ b/src/systems/breadcrumbs/Breadcrumbs.cc @@ -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 " << std::endl; return; @@ -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("topic"); @@ -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); @@ -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; } diff --git a/src/systems/log/LogRecord.cc b/src/systems/log/LogRecord.cc index 233d7049a9..73fe77feee 100644 --- a/src/systems/log/LogRecord.cc +++ b/src/systems/log/LogRecord.cc @@ -538,44 +538,41 @@ bool LogRecordPrivate::SaveModels(const std::set &_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); } } } diff --git a/src/systems/user_commands/UserCommands.cc b/src/systems/user_commands/UserCommands.cc index 25e1a3ec15..c767f89795 100644 --- a/src/systems/user_commands/UserCommands.cc +++ b/src/systems/user_commands/UserCommands.cc @@ -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; } @@ -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 , or , " << "but found more. Only the 1st will be spawned." << std::endl; @@ -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 @@ -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); } diff --git a/test/integration/sdf_frame_semantics.cc b/test/integration/sdf_frame_semantics.cc index 8585952ce8..52e32bbb73 100644 --- a/test/integration/sdf_frame_semantics.cc +++ b/test/integration/sdf_frame_semantics.cc @@ -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); }