From 0127d13e99dcd1d02502d785ce11a07d961c1ea5 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 30 Nov 2021 17:05:02 -0800 Subject: [PATCH 1/4] Fix selection buffer crash after resizing window (#446) * fix selection buffer crash due to resize and incorrect selections Signed-off-by: Ian Chen * test updating full selection buffer texture Signed-off-by: Ian Chen * reenable visual at test Signed-off-by: Ian Chen * fix codecheck Signed-off-by: Ian Chen * testing rgb no depth, full buffer Signed-off-by: Ian Chen * use 1x1 buffer, still no depth data Signed-off-by: Ian Chen * prnt scaling factor Signed-off-by: Ian Chen * disable device ratio Signed-off-by: Ian Chen * reenable depth and utils test Signed-off-by: Ian Chen * disable utils test, add visual at test after resize Signed-off-by: Ian Chen * test texelfetch Signed-off-by: Ian Chen * back to full buffer Signed-off-by: Ian Chen * print ogre log Signed-off-by: Ian Chen * codecheck Signed-off-by: Ian Chen * fixing selection buffer mat script Signed-off-by: Ian Chen * try 1x1 buffer again Signed-off-by: Ian Chen * revert some test changes Signed-off-by: Ian Chen * uncomment tests Signed-off-by: Ian Chen * update scaling factor Signed-off-by: Ian Chen * fix removing selection mat Signed-off-by: Ian Chen * update screenScalingFactor Signed-off-by: Ian Chen * minor tweak Signed-off-by: Ian Chen Co-authored-by: Louise Poubel --- ogre2/src/Ogre2Camera.cc | 1 - ogre2/src/Ogre2RayQuery.cc | 4 + ogre2/src/Ogre2SelectionBuffer.cc | 85 ++++++++++++------- .../programs/GLSL/selection_buffer_fs.glsl | 4 +- .../scripts/selection_buffer.material | 2 + src/Utils.cc | 5 +- src/Utils_TEST.cc | 9 -- test/integration/camera.cc | 29 +++++-- test/integration/scene.cc | 8 -- 9 files changed, 90 insertions(+), 57 deletions(-) diff --git a/ogre2/src/Ogre2Camera.cc b/ogre2/src/Ogre2Camera.cc index 86d1d7b96..c259fff64 100644 --- a/ogre2/src/Ogre2Camera.cc +++ b/ogre2/src/Ogre2Camera.cc @@ -263,7 +263,6 @@ VisualPtr Ogre2Camera::VisualAt(const ignition::math::Vector2i &_mousePos) ignition::math::Vector2i mousePos( static_cast(std::rint(ratio * _mousePos.X())), static_cast(std::rint(ratio * _mousePos.Y()))); - Ogre::Item *ogreItem = this->selectionBuffer->OnSelectionClick( mousePos.X(), mousePos.Y()); diff --git a/ogre2/src/Ogre2RayQuery.cc b/ogre2/src/Ogre2RayQuery.cc index fd9f1d1cc..0ceaee80f 100644 --- a/ogre2/src/Ogre2RayQuery.cc +++ b/ogre2/src/Ogre2RayQuery.cc @@ -128,6 +128,10 @@ RayQueryResult Ogre2RayQuery::ClosestPoint() ////////////////////////////////////////////////// RayQueryResult Ogre2RayQuery::ClosestPointBySelectionBuffer() { + // update selection buffer dimension in case window is resized + this->dataPtr->camera->SelectionBuffer()->SetDimensions( + this->dataPtr->camera->ImageWidth(), this->dataPtr->camera->ImageHeight()); + RayQueryResult result; Ogre::Item *ogreItem = nullptr; math::Vector3d point; diff --git a/ogre2/src/Ogre2SelectionBuffer.cc b/ogre2/src/Ogre2SelectionBuffer.cc index 62686ccb8..72194730c 100644 --- a/ogre2/src/Ogre2SelectionBuffer.cc +++ b/ogre2/src/Ogre2SelectionBuffer.cc @@ -88,6 +88,9 @@ class ignition::rendering::Ogre2SelectionBufferPrivate /// into a render target or render texture. public: Ogre::CompositorWorkspace *ogreCompositorWorkspace = nullptr; + /// \brief Name of the compositor workspace definition + public: std::string ogreCompWorkspaceDefName; + /// \brief The selection buffer material public: Ogre::MaterialPtr selectionMaterial; }; @@ -142,6 +145,16 @@ Ogre2SelectionBuffer::~Ogre2SelectionBuffer() { this->DeleteRTTBuffer(); + // remove selectionMaterial in destructor + // this does not need to be done in DeleteRTTBuffer as we do not need to + // reload the same material every time + if (!this->dataPtr->selectionMaterial.isNull()) + { + Ogre::MaterialManager::getSingleton().remove( + this->dataPtr->selectionMaterial->getName()); + this->dataPtr->selectionMaterial.setNull(); + } + // remove selection buffer camera this->dataPtr->sceneMgr->destroyCamera(this->dataPtr->selectionCamera); } @@ -181,10 +194,17 @@ void Ogre2SelectionBuffer::Update() ///////////////////////////////////////////////// void Ogre2SelectionBuffer::DeleteRTTBuffer() { - if (this->dataPtr->selectionMaterial) + if (this->dataPtr->ogreCompositorWorkspace) { - Ogre::MaterialManager::getSingleton().remove( - this->dataPtr->selectionMaterial->getName()); + // TODO(ahcorde): Remove the workspace. Potential leak here + this->dataPtr->ogreCompMgr->removeWorkspace( + this->dataPtr->ogreCompositorWorkspace); + + this->dataPtr->ogreCompMgr->removeWorkspaceDefinition( + this->dataPtr->ogreCompWorkspaceDefName); + this->dataPtr->ogreCompMgr->removeNodeDefinition( + this->dataPtr->ogreCompWorkspaceDefName + "/Node"); + this->dataPtr->ogreCompositorWorkspace = nullptr; } auto engine = Ogre2RenderEngine::Instance(); @@ -222,11 +242,16 @@ void Ogre2SelectionBuffer::CreateRTTBuffer() // The SelectionBuffer material is defined in script // (selection_buffer.material). std::string matSelectionName = "SelectionBuffer"; - Ogre::MaterialPtr matSelection = - Ogre::MaterialManager::getSingleton().getByName(matSelectionName); - this->dataPtr->selectionMaterial = matSelection->clone( - this->dataPtr->camera->getName() + "_" + matSelectionName); - this->dataPtr->selectionMaterial->load(); + std::string matSelectionCloneName = + this->dataPtr->camera->getName() + "_" + matSelectionName; + if (this->dataPtr->selectionMaterial.isNull()) + { + Ogre::MaterialPtr matSelection = + Ogre::MaterialManager::getSingleton().getByName(matSelectionName); + this->dataPtr->selectionMaterial = matSelection->clone( + matSelectionCloneName); + this->dataPtr->selectionMaterial->load(); + } Ogre::Pass *p = this->dataPtr->selectionMaterial->getTechnique(0)->getPass(0); Ogre::GpuProgramParametersSharedPtr psParams = p->getFragmentProgramParameters(); @@ -252,13 +277,15 @@ void Ogre2SelectionBuffer::CreateRTTBuffer() // create compositor workspace for rendering // Setup the selection buffer compositor. - const Ogre::String workspaceName = "SelectionBufferWorkspace" + + this->dataPtr->ogreCompWorkspaceDefName = "SelectionBufferWorkspace" + this->dataPtr->camera->getName(); + std::string nodeSpaceDefName = + this->dataPtr->ogreCompWorkspaceDefName + "/Node"; + Ogre::CompositorNodeDef *nodeDef = this->dataPtr->ogreCompMgr->addNodeDefinition( - "AutoGen " + Ogre::IdString(workspaceName + - "/Node").getReleaseText()); + nodeSpaceDefName); Ogre::TextureDefinitionBase::TextureDefinition *depthTexDef = nodeDef->addTextureDefinition("depthTexture"); depthTexDef->textureType = Ogre::TextureTypes::Type2D; @@ -346,7 +373,8 @@ void Ogre2SelectionBuffer::CreateRTTBuffer() } Ogre::CompositorWorkspaceDef *workDef = - this->dataPtr->ogreCompMgr->addWorkspaceDefinition(workspaceName); + this->dataPtr->ogreCompMgr->addWorkspaceDefinition( + this->dataPtr->ogreCompWorkspaceDefName); workDef->connectExternal(0, nodeDef->getName(), 0); this->dataPtr->ogreCompositorWorkspace = @@ -354,7 +382,7 @@ void Ogre2SelectionBuffer::CreateRTTBuffer() this->dataPtr->scene->OgreSceneManager(), this->dataPtr->renderTexture, this->dataPtr->selectionCamera, - workspaceName, + this->dataPtr->ogreCompWorkspaceDefName, false); } @@ -369,14 +397,6 @@ void Ogre2SelectionBuffer::SetDimensions( this->dataPtr->height = _height; this->DeleteRTTBuffer(); - - if (this->dataPtr->ogreCompositorWorkspace) - { - // TODO(ahcorde): Remove the workspace. Potential leak here - this->dataPtr->ogreCompMgr->removeWorkspace( - this->dataPtr->ogreCompositorWorkspace); - } - this->CreateRTTBuffer(); } ///////////////////////////////////////////////// @@ -398,6 +418,14 @@ bool Ogre2SelectionBuffer::ExecuteQuery(const int _x, const int _y, if (!this->dataPtr->camera) return false; + // check camera has valid projection matrix + // There could be nan values if camera was resized + Ogre::Matrix4 projectionMatrix = + this->dataPtr->camera->getProjectionMatrix(); + if (projectionMatrix.getTrans().isNaN() || + projectionMatrix.extractQuaternion().isNaN()) + return false; + const unsigned int targetWidth = this->dataPtr->width; const unsigned int targetHeight = this->dataPtr->height; @@ -405,8 +433,8 @@ bool Ogre2SelectionBuffer::ExecuteQuery(const int _x, const int _y, || _y >= static_cast(targetHeight)) return false; - // // 1x1 selection buffer, adapted from rviz - // // http://docs.ros.org/indigo/api/rviz/html/c++/selection__manager_8cpp.html + // 1x1 selection buffer, adapted from rviz + // http://docs.ros.org/indigo/api/rviz/html/c++/selection__manager_8cpp.html unsigned int width = 1; unsigned int height = 1; float x1 = static_cast(_x) / @@ -425,10 +453,10 @@ bool Ogre2SelectionBuffer::ExecuteQuery(const int _x, const int _y, transMatrix[0][3] -= x1+x2; transMatrix[1][3] += y1+y2; Ogre::Matrix4 customProjectionMatrix = - scaleMatrix * transMatrix * this->dataPtr->camera->getProjectionMatrix(); - - this->dataPtr->selectionCamera->setCustomProjectionMatrix(true, - customProjectionMatrix); + scaleMatrix * transMatrix * + this->dataPtr->camera->getProjectionMatrix(); + this->dataPtr->selectionCamera->setCustomProjectionMatrix(true, + customProjectionMatrix); this->dataPtr->selectionCamera->setPosition( this->dataPtr->camera->getDerivedPosition()); @@ -440,9 +468,8 @@ bool Ogre2SelectionBuffer::ExecuteQuery(const int _x, const int _y, Ogre::Image2 image; image.convertFromTexture(this->dataPtr->renderTexture, 0, 0); - Ogre::ColourValue pixel = image.getColourAt(0, 0, 0, 0); - // Ogre::ColourValue pixel = image.getColourAt(_x, _y, 0, 0); + float color = pixel[3]; uint32_t *rgba = reinterpret_cast(&color); unsigned int r = *rgba >> 24 & 0xFF; diff --git a/ogre2/src/media/materials/programs/GLSL/selection_buffer_fs.glsl b/ogre2/src/media/materials/programs/GLSL/selection_buffer_fs.glsl index d9acd041e..a80bcf4ad 100644 --- a/ogre2/src/media/materials/programs/GLSL/selection_buffer_fs.glsl +++ b/ogre2/src/media/materials/programs/GLSL/selection_buffer_fs.glsl @@ -25,6 +25,7 @@ in block uniform sampler2D colorTexture; uniform sampler2D depthTexture; +uniform vec4 colorTexResolution; out vec4 fragColor; @@ -58,7 +59,8 @@ void main() point = vec3(inf); // color - vec4 color = texture(colorTexture, inPs.uv0); + vec4 color = texelFetch(colorTexture, + ivec2(inPs.uv0 * colorTexResolution.xy), 0); float rgba = packFloat(color); diff --git a/ogre2/src/media/materials/scripts/selection_buffer.material b/ogre2/src/media/materials/scripts/selection_buffer.material index 18649f55d..2bcbbc00b 100644 --- a/ogre2/src/media/materials/scripts/selection_buffer.material +++ b/ogre2/src/media/materials/scripts/selection_buffer.material @@ -33,6 +33,8 @@ fragment_program selection_buffer_fs_GLSL glsl { param_named colorTexture int 0 param_named depthTexture int 1 + + param_named_auto colorTexResolution texture_size 0 } } diff --git a/src/Utils.cc b/src/Utils.cc index 0ac5902c5..394e7ab71 100644 --- a/src/Utils.cc +++ b/src/Utils.cc @@ -104,7 +104,10 @@ float screenScalingFactor() { // todo(anyone) set device pixel ratio for high dpi displays on Windows float ratio = 1.0; -#ifdef __linux__ + + // the scaling factor seems to cause issues with mouse picking. + // see https://github.com/ignitionrobotics/ign-gazebo/issues/147 +#if 0 auto closeDisplay = [](Display * display) { if (display) diff --git a/src/Utils_TEST.cc b/src/Utils_TEST.cc index d75e57daa..6406bac27 100644 --- a/src/Utils_TEST.cc +++ b/src/Utils_TEST.cc @@ -121,15 +121,6 @@ void UtilTest::ClickToScene(const std::string &_renderEngine) root->AddChild(camera); camera->Update(); - if (_renderEngine == "ogre2") - { - // tests using selection buffer fail on CI, see issue #170 - // https://github.com/ignitionrobotics/ign-rendering/issues/170 - igndbg << "Selection buffer based screenToScene test is disabled in " - << _renderEngine << "." << std::endl; - return; - } - // API without RayQueryResult and default max distance result = screenToScene(centerClick, camera, rayQuery, rayResult); diff --git a/test/integration/camera.cc b/test/integration/camera.cc index 4457e3b36..95619639d 100644 --- a/test/integration/camera.cc +++ b/test/integration/camera.cc @@ -187,14 +187,6 @@ void CameraTest::VisualAt(const std::string &_renderEngine) << _renderEngine << std::endl; return; } - else if (_renderEngine == "ogre2") - { - // VisualAt tests fail on CI, see issue #170 - // https://github.com/ignitionrobotics/ign-rendering/issues/170 - igndbg << "VisualAt test is disabled in " << _renderEngine << "." - << std::endl; - return; - } // create and populate scene RenderEngine *engine = rendering::engine(_renderEngine); @@ -285,6 +277,27 @@ void CameraTest::VisualAt(const std::string &_renderEngine) } } + // change camera size + camera->SetImageWidth(1200); + camera->SetImageHeight(800); + + // render a few frames + for (auto i = 0; i < 30; ++i) + { + camera->Update(); + } + + // test that VisualAt still works after resize + { + unsigned int x = 300u; + auto vis = camera->VisualAt(math::Vector2i(x, camera->ImageHeight() / 2)); + EXPECT_NE(nullptr, vis) << "X: " << x; + if (vis) + { + EXPECT_EQ("sphere", vis->Name()); + } + } + // Clean up engine->DestroyScene(scene); rendering::unloadEngine(engine->Name()); diff --git a/test/integration/scene.cc b/test/integration/scene.cc index ebca2cd74..79e657e3c 100644 --- a/test/integration/scene.cc +++ b/test/integration/scene.cc @@ -154,14 +154,6 @@ void SceneTest::VisualAt(const std::string &_renderEngine) << _renderEngine << std::endl; return; } - else if (_renderEngine == "ogre2") - { - // VisualAt tests fail on CI, see issue #170 - // https://github.com/ignitionrobotics/ign-rendering/issues/170 - igndbg << "VisualAt test is disabled in " << _renderEngine << "." - << std::endl; - return; - } // create and populate scene RenderEngine *engine = rendering::engine(_renderEngine); From ae292a88bd752822e0c0f6ed6fd6029e3fc64d0e Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Wed, 1 Dec 2021 22:02:44 +0000 Subject: [PATCH 2/4] [Metal] update depth camera and selection buffer shaders to match #446 (#498) - Add new param colorTexResolution to the selection buffer shader - Implement the Metal equivalent of texelFetch in the shaders Signed-off-by: Rhys Mainwaring --- .../materials/programs/Metal/depth_camera_final_fs.metal | 7 ++++--- .../materials/programs/Metal/selection_buffer_fs.metal | 7 ++++++- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/ogre2/src/media/materials/programs/Metal/depth_camera_final_fs.metal b/ogre2/src/media/materials/programs/Metal/depth_camera_final_fs.metal index 90454a833..8133f0872 100644 --- a/ogre2/src/media/materials/programs/Metal/depth_camera_final_fs.metal +++ b/ogre2/src/media/materials/programs/Metal/depth_camera_final_fs.metal @@ -49,9 +49,10 @@ fragment float4 main_metal // values close to 0 get rounded to 0) // // See https://github.com/ignitionrobotics/ign-rendering/issues/332 - // float4 p = texelFetch(inputTexture, int2(inPs.uv0 * params.texResolution.xy), 0); - // TODO - establish Metal equivalent - use standard sampler as interim approx. - float4 p = inputTexture.sample(inputSampler, inPs.uv0); + // Either: Metal equivalent of texelFetch + float4 p = inputTexture.read(uint2(inPs.uv0 * params.texResolution.xy), 0); + // Or: Use standard sampler + // float4 p = inputTexture.sample(inputSampler, inPs.uv0); float3 point = p.xyz; diff --git a/ogre2/src/media/materials/programs/Metal/selection_buffer_fs.metal b/ogre2/src/media/materials/programs/Metal/selection_buffer_fs.metal index 5620d1c12..28ce70f4b 100644 --- a/ogre2/src/media/materials/programs/Metal/selection_buffer_fs.metal +++ b/ogre2/src/media/materials/programs/Metal/selection_buffer_fs.metal @@ -29,6 +29,7 @@ struct Params float2 projectionParams; float far; float inf; + float4 colorTexResolution; }; float packFloat(float4 color) @@ -66,7 +67,11 @@ fragment float4 main_metal point = float3(p.inf); // color - float4 color = colorTexture.sample(colorSampler, inPs.uv0); + // Either: Metal equivalent of texelFetch + float4 color = colorTexture.read( + uint2(inPs.uv0 * p.colorTexResolution.xy), 0); + // Or: Use standard sampler + // float4 color = colorTexture.sample(colorSampler, inPs.uv0); float rgba = packFloat(color); From f02561071184e0309e25a780109f6ef31659ad00 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 3 Dec 2021 11:43:46 -0800 Subject: [PATCH 3/4] partial fix for emissive map (#501) Signed-off-by: Ian Chen --- ogre2/src/Ogre2Material.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ogre2/src/Ogre2Material.cc b/ogre2/src/Ogre2Material.cc index 6e5215220..5ca027d98 100644 --- a/ogre2/src/Ogre2Material.cc +++ b/ogre2/src/Ogre2Material.cc @@ -541,7 +541,8 @@ void Ogre2Material::ClearLightMap() this->lightMapUvSet = 0u; // in ogre 2.2, we swtiched to use the emissive map slot for light map - this->ogreDatablock->setTexture(Ogre::PBSM_EMISSIVE, this->lightMapName); + if (this->ogreDatablock->getUseEmissiveAsLightmap()) + this->ogreDatablock->setTexture(Ogre::PBSM_EMISSIVE, this->lightMapName); this->ogreDatablock->setUseEmissiveAsLightmap(false); } From 6c463bdf2e33f5627d027126f34bf830281b9864 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 7 Dec 2021 11:19:32 -0800 Subject: [PATCH 4/4] Fix loading grayscale emissive map (#503) * partial fix for emissive map Signed-off-by: Ian Chen * convert grayscale emissive to rgb Signed-off-by: Ian Chen * testing upload Signed-off-by: Ian Chen * upload data to gpu working Signed-off-by: Ian Chen * remove unused code Signed-off-by: Ian Chen * fix loading Signed-off-by: Ian Chen * style Signed-off-by: Ian Chen --- ogre2/src/Ogre2Material.cc | 75 ++++++++++++++++++++++++++++++++++++-- 1 file changed, 71 insertions(+), 4 deletions(-) diff --git a/ogre2/src/Ogre2Material.cc b/ogre2/src/Ogre2Material.cc index 5ca027d98..f33ea0fea 100644 --- a/ogre2/src/Ogre2Material.cc +++ b/ogre2/src/Ogre2Material.cc @@ -35,6 +35,7 @@ #include #include +#include #include "ignition/rendering/ShaderParams.hh" #include "ignition/rendering/ShaderType.hh" @@ -636,16 +637,82 @@ void Ogre2Material::SetTextureMapImpl(const std::string &_texture, } } + Ogre::Root *root = Ogre2RenderEngine::Instance()->OgreRoot(); + Ogre::TextureGpuManager *textureMgr = + root->getRenderSystem()->getTextureGpuManager(); + + // workaround for grayscale emissive texture + // convert to RGB otherwise the emissive map is rendered red + if (_type == Ogre::PBSM_EMISSIVE && + !this->ogreDatablock->getUseEmissiveAsLightmap()) + { + common::Image img(_texture); + // check for 8 bit pixel + if (img.BPP() == 8u) + { + std::string parentPath = common::parentPath(_texture); + // set a custom name for the rgb texture by appending ign_ prefix + std::string rgbTexName = "ign_" + baseName; + baseName = rgbTexName; + std::string filename = common::joinPaths(parentPath, rgbTexName); + auto tex = textureMgr->findTextureNoThrow(rgbTexName); + if (!tex) + { + ignmsg << "Grayscale emissive texture detected. Converting to RGB: " + << rgbTexName << std::endl; + // need to be 4 channels for gpu texture + unsigned int channels = 4u; + unsigned int size = img.Width() * img.Height() * channels; + unsigned char *data = new unsigned char[size]; + for (unsigned int i = 0; i < img.Height(); ++i) + { + for (unsigned int j = 0; j < img.Width(); ++j) + { + // flip Y + math::Color c = img.Pixel(j, img.Height() - i - 1u); + unsigned int idx = i * img.Width() * channels + j * channels; + data[idx] = static_cast(c.R() * 255u); + data[idx + 1u] = static_cast(c.R() * 255u); + data[idx + 2u] = static_cast(c.R() * 255u); + data[idx + 3u] = 255u; + } + } + + // create the gpu texture + Ogre::uint32 textureFlags = 0; + textureFlags |= Ogre::TextureFlags::AutomaticBatching; + if (this->ogreDatablock->suggestUsingSRGB(_type)) + textureFlags |= Ogre::TextureFlags::PrefersLoadingFromFileAsSRGB; + Ogre::TextureGpu *texture = textureMgr->createOrRetrieveTexture( + rgbTexName, + Ogre::GpuPageOutStrategy::Discard, + textureFlags | Ogre::TextureFlags::ManualTexture, + Ogre::TextureTypes::Type2D, + Ogre::ResourceGroupManager::AUTODETECT_RESOURCE_GROUP_NAME, + 0u); + + texture->setPixelFormat(Ogre::PFG_RGBA8_UNORM_SRGB); + texture->setTextureType(Ogre::TextureTypes::Type2D); + texture->setNumMipmaps(1u); + texture->setResolution(img.Width(), img.Height()); + texture->scheduleTransitionTo(Ogre::GpuResidency::Resident); + texture->waitForData(); + + // upload raw color image data to gpu texture + Ogre::Image2 image; + image.loadDynamicImage(data, false, texture); + image.uploadTo(texture, 0, 0); + delete [] data; + } + } + } + Ogre::HlmsSamplerblock samplerBlockRef; samplerBlockRef.mU = Ogre::TAM_WRAP; samplerBlockRef.mV = Ogre::TAM_WRAP; samplerBlockRef.mW = Ogre::TAM_WRAP; this->ogreDatablock->setTexture(_type, baseName, &samplerBlockRef); - - Ogre::Root *root = Ogre2RenderEngine::Instance()->OgreRoot(); - Ogre::TextureGpuManager *textureMgr = - root->getRenderSystem()->getTextureGpuManager(); auto tex = textureMgr->findTextureNoThrow(baseName); if (tex)