diff --git a/src/gui/plugins/align_tool/AlignTool.cc b/src/gui/plugins/align_tool/AlignTool.cc index a2d965ef26..ca397093d3 100644 --- a/src/gui/plugins/align_tool/AlignTool.cc +++ b/src/gui/plugins/align_tool/AlignTool.cc @@ -365,8 +365,7 @@ void AlignTool::Align() continue; if (vis->HasUserData("gazebo-entity") && - std::get(vis->UserData("gazebo-entity")) == - static_cast(entityId)) + std::get(vis->UserData("gazebo-entity")) == entityId) { // Check here to see if visual is top level or not, continue if not auto topLevelVis = this->TopLevelVisual(this->dataPtr->scene, vis); diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index 854648cb58..b5bef6d49d 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -1029,7 +1029,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->dataPtr->renderUtil.ViewTransparent(targetEntity); } else @@ -1055,7 +1055,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->dataPtr->renderUtil.ViewCOM(targetEntity); } else @@ -1081,7 +1081,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->dataPtr->renderUtil.ViewInertia(targetEntity); } else @@ -1107,7 +1107,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->dataPtr->renderUtil.ViewJoints(targetEntity); } else @@ -1133,7 +1133,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->dataPtr->renderUtil.ViewWireframes(targetEntity); } else @@ -1159,7 +1159,7 @@ void IgnRenderer::Render(RenderSync *_renderSync) if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->dataPtr->renderUtil.ViewCollisions(targetEntity); } else diff --git a/src/gui/plugins/select_entities/SelectEntities.cc b/src/gui/plugins/select_entities/SelectEntities.cc index 921dd03242..396360b34a 100644 --- a/src/gui/plugins/select_entities/SelectEntities.cc +++ b/src/gui/plugins/select_entities/SelectEntities.cc @@ -173,7 +173,8 @@ void SelectEntitiesPrivate::HandleEntitySelection() Entity entityId = kNullEntity; try { - entityId = std::get(visualToHighLight->UserData("gazebo-entity")); + entityId = std::get( + visualToHighLight->UserData("gazebo-entity")); } catch(std::bad_variant_access &_e) { @@ -213,7 +214,7 @@ void SelectEntitiesPrivate::HandleEntitySelection() Entity entityId = kNullEntity; try { - entityId = std::get(visual->UserData("gazebo-entity")); + entityId = std::get(visual->UserData("gazebo-entity")); } catch(std::bad_variant_access &e) { @@ -244,7 +245,7 @@ void SelectEntitiesPrivate::LowlightNode(const rendering::VisualPtr &_visual) { try { - entityId = std::get(_visual->UserData("gazebo-entity")); + entityId = std::get(_visual->UserData("gazebo-entity")); } catch(std::bad_variant_access &) { @@ -272,7 +273,7 @@ void SelectEntitiesPrivate::HighlightNode(const rendering::VisualPtr &_visual) Entity entityId = kNullEntity; try { - entityId = std::get(_visual->UserData("gazebo-entity")); + entityId = std::get(_visual->UserData("gazebo-entity")); } catch(std::bad_variant_access &) { @@ -359,7 +360,7 @@ void SelectEntitiesPrivate::SetSelectedEntity( { try { - entityId = std::get(topLevelVisual->UserData("gazebo-entity")); + entityId = std::get(topLevelVisual->UserData("gazebo-entity")); } catch(std::bad_variant_access &) { @@ -545,7 +546,7 @@ bool SelectEntities::eventFilter(QObject *_obj, QEvent *_event) Entity entityId = kNullEntity; try { - entityId = std::get(visual->UserData("gazebo-entity")); + entityId = std::get(visual->UserData("gazebo-entity")); } catch(std::bad_variant_access &) { diff --git a/src/gui/plugins/transform_control/TransformControl.cc b/src/gui/plugins/transform_control/TransformControl.cc index f897b16b56..732aafe500 100644 --- a/src/gui/plugins/transform_control/TransformControl.cc +++ b/src/gui/plugins/transform_control/TransformControl.cc @@ -801,8 +801,7 @@ void TransformControlPrivate::HandleTransform() auto entityId = kNullEntity; try { - entityId = static_cast( - std::get(visual->UserData("gazebo-entity"))); + entityId = std::get(visual->UserData("gazebo-entity")); } catch (std::bad_variant_access &) { diff --git a/src/gui/plugins/view_angle/ViewAngle.cc b/src/gui/plugins/view_angle/ViewAngle.cc index 8f3b34f431..e561ac6677 100644 --- a/src/gui/plugins/view_angle/ViewAngle.cc +++ b/src/gui/plugins/view_angle/ViewAngle.cc @@ -377,8 +377,7 @@ void ViewAnglePrivate::OnRender() try { - if (std::get(vis->UserData("gazebo-entity")) != - static_cast(entity)) + if (std::get(vis->UserData("gazebo-entity")) != entity) { continue; } diff --git a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc index 68d6a16733..b9dd2f133c 100644 --- a/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc +++ b/src/gui/plugins/visualization_capabilities/VisualizationCapabilities.cc @@ -806,7 +806,7 @@ void VisualizationCapabilitiesPrivate::OnRender() if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->ViewCOM(targetEntity); } else @@ -832,7 +832,7 @@ void VisualizationCapabilitiesPrivate::OnRender() if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->ViewInertia(targetEntity); } else @@ -858,7 +858,7 @@ void VisualizationCapabilitiesPrivate::OnRender() if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->ViewTransparent(targetEntity); } else @@ -884,7 +884,7 @@ void VisualizationCapabilitiesPrivate::OnRender() if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->ViewCollisions(targetEntity); } else @@ -910,7 +910,7 @@ void VisualizationCapabilitiesPrivate::OnRender() if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->ViewJoints(targetEntity); } else @@ -936,7 +936,7 @@ void VisualizationCapabilitiesPrivate::OnRender() if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->ViewWireframes(targetEntity); } else @@ -961,7 +961,7 @@ void VisualizationCapabilitiesPrivate::OnRender() if (targetVis && targetVis->HasUserData("gazebo-entity")) { Entity targetEntity = - std::get(targetVis->UserData("gazebo-entity")); + std::get(targetVis->UserData("gazebo-entity")); this->ViewFrames(targetEntity); } else @@ -1087,7 +1087,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateJointVisual( rendering::VisualPtr jointVis = std::dynamic_pointer_cast(jointVisual); - jointVis->SetUserData("gazebo-entity", static_cast(_id)); + jointVis->SetUserData("gazebo-entity", _id); jointVis->SetUserData("pause-update", static_cast(0)); jointVis->SetUserData("gui-only", static_cast(true)); jointVis->SetLocalPose(_joint.RawPose()); @@ -1132,7 +1132,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateInertiaVisual( rendering::VisualPtr inertiaVis = std::dynamic_pointer_cast(inertiaVisual); - inertiaVis->SetUserData("gazebo-entity", static_cast(_id)); + inertiaVis->SetUserData("gazebo-entity", _id); inertiaVis->SetUserData("pause-update", static_cast(0)); inertiaVis->SetUserData("gui-only", static_cast(true)); this->visuals[_id] = inertiaVis; @@ -1487,7 +1487,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCollisionVisual( return vis; } rendering::VisualPtr visualVis = this->scene->CreateVisual(name); - visualVis->SetUserData("gazebo-entity", static_cast(_id)); + visualVis->SetUserData("gazebo-entity", _id); visualVis->SetUserData("pause-update", static_cast(0)); visualVis->SetLocalPose(_visual.RawPose()); @@ -1611,7 +1611,7 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::CreateCOMVisual( rendering::VisualPtr comVis = std::dynamic_pointer_cast(comVisual); - comVis->SetUserData("gazebo-entity", static_cast(_id)); + comVis->SetUserData("gazebo-entity", _id); comVis->SetUserData("pause-update", static_cast(0)); comVis->SetUserData("gui-only", static_cast(true)); this->visuals[_id] = comVis; @@ -1682,7 +1682,8 @@ rendering::VisualPtr VisualizationCapabilitiesPrivate::VisualByEntity( try { - Entity visualEntity = std::get(visual->UserData("gazebo-entity")); + Entity visualEntity = std::get( + visual->UserData("gazebo-entity")); if (visualEntity == _entity) { diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index 2fda2d34c5..9c5aef2de1 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -1277,7 +1277,7 @@ void RenderUtil::Update() // this functionality is needed for temporal placement of a // visual such as an align preview updateNode = std::get(vis->UserData("pause-update")); - entityId = std::get(vis->UserData("gazebo-entity")); + entityId = std::get(vis->UserData("gazebo-entity")); } if ((this->dataPtr->transformActive && (pose.first == this->dataPtr->selectedEntities.back() || @@ -2690,7 +2690,7 @@ void RenderUtil::SetSelectedEntity(const rendering::NodePtr &_node) Entity entityId = kNullEntity; if (vis) - entityId = std::get(vis->UserData("gazebo-entity")); + entityId = std::get(vis->UserData("gazebo-entity")); if (entityId == kNullEntity) return; @@ -2750,7 +2750,7 @@ void RenderUtilPrivate::HighlightNode(const rendering::NodePtr &_node) auto vis = std::dynamic_pointer_cast(_node); Entity entityId = kNullEntity; if (vis) - entityId = std::get(vis->UserData("gazebo-entity")); + entityId = std::get(vis->UserData("gazebo-entity")); // If the entity is not found in the existing map, create a wire box auto wireBoxIt = this->wireBoxes.find(entityId); if (wireBoxIt == this->wireBoxes.end()) @@ -2808,7 +2808,7 @@ void RenderUtilPrivate::LowlightNode(const rendering::NodePtr &_node) auto vis = std::dynamic_pointer_cast(_node); Entity entityId = kNullEntity; if (vis) - entityId = std::get(vis->UserData("gazebo-entity")); + entityId = std::get(vis->UserData("gazebo-entity")); if (this->wireBoxes.find(entityId) != this->wireBoxes.end()) { ignition::rendering::WireBoxPtr wireBox = diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index bc71c91d8f..43270415d5 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -195,8 +195,7 @@ rendering::VisualPtr SceneManager::CreateModel(Entity _id, rendering::VisualPtr modelVis = this->dataPtr->scene->CreateVisual(name); - // \todo(anyone) change to uint64_t once UserData supports this type - modelVis->SetUserData("gazebo-entity", static_cast(_id)); + modelVis->SetUserData("gazebo-entity", _id); modelVis->SetUserData("pause-update", static_cast(0)); modelVis->SetLocalPose(_model.RawPose()); this->dataPtr->visuals[_id] = modelVis; @@ -241,7 +240,7 @@ rendering::VisualPtr SceneManager::CreateLink(Entity _id, if (parent) name = parent->Name() + "::" + name; rendering::VisualPtr linkVis = this->dataPtr->scene->CreateVisual(name); - linkVis->SetUserData("gazebo-entity", static_cast(_id)); + linkVis->SetUserData("gazebo-entity", _id); linkVis->SetUserData("pause-update", static_cast(0)); linkVis->SetLocalPose(_link.RawPose()); this->dataPtr->visuals[_id] = linkVis; @@ -287,7 +286,7 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id, if (parent) name = parent->Name() + "::" + name; rendering::VisualPtr visualVis = this->dataPtr->scene->CreateVisual(name); - visualVis->SetUserData("gazebo-entity", static_cast(_id)); + visualVis->SetUserData("gazebo-entity", _id); visualVis->SetUserData("pause-update", static_cast(0)); visualVis->SetLocalPose(_visual.RawPose()); @@ -548,7 +547,7 @@ std::pair> SceneManager::CopyVisual( } this->dataPtr->visuals[childId] = childVisual; - childVisual->SetUserData("gazebo-entity", static_cast(childId)); + childVisual->SetUserData("gazebo-entity", childId); childVisual->SetUserData("pause-update", static_cast(0)); childVisualIds.push_back(childId); @@ -564,7 +563,7 @@ std::pair> SceneManager::CopyVisual( } else { - clonedVisual->SetUserData("gazebo-entity", static_cast(_id)); + clonedVisual->SetUserData("gazebo-entity", _id); clonedVisual->SetUserData("pause-update", static_cast(0)); result = {clonedVisual, std::move(childVisualIds)}; @@ -1201,7 +1200,7 @@ rendering::VisualPtr SceneManager::CreateActor(Entity _id, rendering::VisualPtr actorVisual = this->dataPtr->scene->CreateVisual(name); actorVisual->SetLocalPose(_actor.RawPose()); actorVisual->AddGeometry(actorMesh); - actorVisual->SetUserData("gazebo-entity", static_cast(_id)); + actorVisual->SetUserData("gazebo-entity", _id); actorVisual->SetUserData("pause-update", static_cast(0)); this->dataPtr->visuals[_id] = actorVisual; @@ -1274,7 +1273,7 @@ rendering::VisualPtr SceneManager::CreateLightVisual(Entity _id, rendering::VisualPtr lightVis = std::dynamic_pointer_cast( lightVisual); - lightVis->SetUserData("gazebo-entity", static_cast(_id)); + lightVis->SetUserData("gazebo-entity", _id); lightVis->SetUserData("pause-update", static_cast(0)); this->dataPtr->visuals[_id] = lightVis; @@ -1408,7 +1407,7 @@ rendering::VisualPtr SceneManager::CreateInertiaVisual(Entity _id, rendering::VisualPtr inertiaVis = std::dynamic_pointer_cast(inertiaVisual); - inertiaVis->SetUserData("gazebo-entity", static_cast(_id)); + inertiaVis->SetUserData("gazebo-entity", _id); inertiaVis->SetUserData("pause-update", static_cast(0)); inertiaVis->SetUserData("gui-only", static_cast(true)); this->dataPtr->visuals[_id] = inertiaVis; @@ -1541,7 +1540,7 @@ rendering::VisualPtr SceneManager::CreateJointVisual( rendering::VisualPtr jointVis = std::dynamic_pointer_cast(jointVisual); - jointVis->SetUserData("gazebo-entity", static_cast(_id)); + jointVis->SetUserData("gazebo-entity", _id); jointVis->SetUserData("pause-update", static_cast(0)); jointVis->SetUserData("gui-only", static_cast(true)); jointVis->SetLocalPose(_joint.RawPose()); @@ -1590,7 +1589,7 @@ rendering::VisualPtr SceneManager::CreateCOMVisual(Entity _id, rendering::VisualPtr comVis = std::dynamic_pointer_cast(comVisual); - comVis->SetUserData("gazebo-entity", static_cast(_id)); + comVis->SetUserData("gazebo-entity", _id); comVis->SetUserData("pause-update", static_cast(0)); comVis->SetUserData("gui-only", static_cast(true)); this->dataPtr->visuals[_id] = comVis; @@ -1803,8 +1802,7 @@ bool SceneManager::AddSensor(Entity _gazeboId, const std::string &_sensorName, return false; } - // \todo(anyone) change to uint64_t once UserData supports this type - sensor->SetUserData("gazebo-entity", static_cast(_gazeboId)); + sensor->SetUserData("gazebo-entity", _gazeboId); if (parent) { diff --git a/src/systems/shader_param/ShaderParam.cc b/src/systems/shader_param/ShaderParam.cc index b16173481b..eeabde451f 100644 --- a/src/systems/shader_param/ShaderParam.cc +++ b/src/systems/shader_param/ShaderParam.cc @@ -284,11 +284,9 @@ void ShaderParamPrivate::OnUpdate() nodes.pop_front(); if (n && n->HasUserData("gazebo-entity")) { - // RenderUti stores gazebo-entity user data as int - // \todo(anyone) Change this to uint64_t in Ignition H? auto variant = n->UserData("gazebo-entity"); - const int *value = std::get_if(&variant); - if (value && *value == static_cast(this->entity)) + const uint64_t *value = std::get_if(&variant); + if (value && *value == this->entity) { this->visual = std::dynamic_pointer_cast(n); break; diff --git a/test/integration/sensors_system.cc b/test/integration/sensors_system.cc index a3831aec73..8c0387ea0f 100644 --- a/test/integration/sensors_system.cc +++ b/test/integration/sensors_system.cc @@ -75,8 +75,7 @@ void OnPostRender() EXPECT_TRUE(sensor->HasUserData("gazebo-entity")); auto variant = sensor->UserData("gazebo-entity"); - // todo(anyone) change int to uint64_t once user data supports it - const int *value = std::get_if(&variant); + const uint64_t *value = std::get_if(&variant); ASSERT_TRUE(value); g_sensorEntityIds.insert(*value); }