diff --git a/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh b/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh index 743012557..677548f98 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2RenderEngine.hh @@ -90,8 +90,8 @@ namespace ignition // Documentation Inherited. public: virtual std::string Name() const override; - /// \brief Add path to resourcea in ogre2's resource manager - /// \param[in] _uri Reousrce path in the form of an uri + /// \brief Add path to resource in ogre2's resource manager + /// \param[in] _uri Resource path in the form of an uri public: void AddResourcePath(const std::string &_uri) override; /// \brief Get the ogre2 root object diff --git a/ogre2/src/Ogre2ThermalCamera.cc b/ogre2/src/Ogre2ThermalCamera.cc index d31299bcb..504afa0e4 100644 --- a/ogre2/src/Ogre2ThermalCamera.cc +++ b/ogre2/src/Ogre2ThermalCamera.cc @@ -24,14 +24,30 @@ #endif #include + +#include #include +#include +#include +#include + +#ifdef _MSC_VER +#pragma warning(push, 0) +#endif +#include +#include +#ifdef _MSC_VER +#pragma warning(pop) +#endif #include +#include #include #include "ignition/rendering/RenderTypes.hh" #include "ignition/rendering/ogre2/Ogre2Conversions.hh" #include "ignition/rendering/ogre2/Ogre2Includes.hh" +#include "ignition/rendering/ogre2/Ogre2Material.hh" #include "ignition/rendering/ogre2/Ogre2RenderEngine.hh" #include "ignition/rendering/ogre2/Ogre2RenderTarget.hh" #include "ignition/rendering/ogre2/Ogre2RenderTypes.hh" @@ -52,7 +68,9 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener { /// \brief constructor /// \param[in] _scene the scene manager responsible for rendering - public: explicit Ogre2ThermalCameraMaterialSwitcher(Ogre2ScenePtr _scene); + /// \param[in] _name the name of the thermal camera + public: explicit Ogre2ThermalCameraMaterialSwitcher(Ogre2ScenePtr _scene, + const std::string & _name); /// \brief destructor public: ~Ogre2ThermalCameraMaterialSwitcher() = default; @@ -75,13 +93,32 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener /// \brief Pointer to the heat source material private: Ogre::MaterialPtr heatSourceMaterial; + /// \brief Pointer to the "base" heat signature material. + /// All renderable items with a heat signature texture use their own + /// copy of this base material, with the item's specific heat + /// signature texture applied to it + private: Ogre::MaterialPtr baseHeatSigMaterial; + + /// \brief A map of all items that have a heat signature material. + /// The key is the item's ID, and the value is the heat signature + /// for that item. + private: std::unordered_map + heatSignatureMaterials; + + /// \brief The name of the thermal camera sensor + private: const std::string name; + + /// \brief The thermal camera + private: const Ogre::Camera* ogreCamera{nullptr}; + /// \brief Custom parameter index of temperature data in an ogre subitem. /// This has to match the custom index specifed in ThermalHeatSource material /// script in media/materials/scripts/thermal_camera.material private: const unsigned int customParamIdx = 10u; /// \brief A map of ogre sub item pointer to their original hlms material - private: std::map datablockMap; + private: std::unordered_map + datablockMap; }; } } @@ -130,6 +167,11 @@ class ignition::rendering::Ogre2ThermalCameraPrivate /// \brief Pointer to material switcher public: std::unique_ptr thermalMaterialSwitcher = nullptr; + + /// \brief Add variation to temperature values based on object rgb values + /// This only affects objects that are not heat sources + /// TODO(anyone) add API for setting this value? + public: bool rgbToTemp = true; }; using namespace ignition; @@ -137,7 +179,7 @@ using namespace rendering; ////////////////////////////////////////////////// Ogre2ThermalCameraMaterialSwitcher::Ogre2ThermalCameraMaterialSwitcher( - Ogre2ScenePtr _scene) + Ogre2ScenePtr _scene, const std::string & _name) : name(_name) { this->scene = _scene; // plain opaque material @@ -147,6 +189,11 @@ Ogre2ThermalCameraMaterialSwitcher::Ogre2ThermalCameraMaterialSwitcher( this->heatSourceMaterial = res.staticCast(); this->heatSourceMaterial->load(); + + this->baseHeatSigMaterial = Ogre::MaterialManager::getSingleton(). + getByName("ThermalHeatSignature"); + + this->ogreCamera = this->scene->OgreSceneManager()->findCamera(this->name); } ////////////////////////////////////////////////// @@ -164,7 +211,7 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( Ogre::MovableObject *object = itor.peekNext(); Ogre::Item *item = static_cast(object); - std::string tempKey = "temperature"; + const std::string tempKey = "temperature"; // get visual Ogre::Any userAny = item->getUserObjectBindings().getUserAny(); if (!userAny.isEmpty() && userAny.getType() == typeid(unsigned int)) @@ -183,7 +230,7 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( // get temperature Variant tempAny = ogreVisual->UserData(tempKey); - if (tempAny.index() != 0) + if (tempAny.index() != 0 && !std::holds_alternative(tempAny)) { float temp = -1.0; try @@ -213,8 +260,6 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( // only accept positive temperature (in kelvin) if (temp >= 0.0) { - // set visibility flag so thermal camera can see it - item->addVisibilityFlags(0x10000000); for (unsigned int i = 0; i < item->getNumSubItems(); ++i) { Ogre::SubItem *subItem = item->getSubItem(i); @@ -223,8 +268,12 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( // normalize temperature value float color = temp * 100.0 / static_cast(std::numeric_limits::max()); + + // set g, b, a to 0. This will be used by shaders to determine + // if particular fragment is a heat source or not + // see media/materials/programs/thermal_camera_fs.glsl subItem->setCustomParameter(this->customParamIdx, - Ogre::Vector4(color, color, color, 1.0)); + Ogre::Vector4(color, 0, 0, 0.0)); } Ogre::HlmsDatablock *datablock = subItem->getDatablock(); this->datablockMap[subItem] = datablock; @@ -233,6 +282,96 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( } } } + // get heat signature and the corresponding min/max temperature values + else if (auto heatSignature = std::get_if(&tempAny)) + { + // if this is the first time rendering the heat signature, + // we need to make sure that the texture is loaded and applied to + // the heat signature material before loading the material + if (this->heatSignatureMaterials.find(item->getId()) == + this->heatSignatureMaterials.end()) + { + // make sure the texture is in ogre's resource path + const auto &texture = *heatSignature; + auto engine = Ogre2RenderEngine::Instance(); + engine->AddResourcePath(texture); + + // create a material for this item, now that the texture has been + // searched for. We must clone the base heat signature material since + // different items may use different textures. We also append the + // item's ID to the end of the new material name to ensure new + // material uniqueness in case two items use the same heat signature + // texture, but have different temperature ranges + std::string baseName = common::basename(texture); + auto heatSignatureMaterial = this->baseHeatSigMaterial->clone( + this->name + "_" + baseName + "_" + + Ogre::StringConverter::toString(item->getId())); + auto textureUnitStatePtr = heatSignatureMaterial-> + getTechnique(0)->getPass(0)->getTextureUnitState(0); + Ogre::String textureName = baseName; + textureUnitStatePtr->setTextureName(textureName); + + // set temperature range for the heat signature + auto minTempVariant = ogreVisual->UserData("minTemp"); + auto maxTempVariant = ogreVisual->UserData("maxTemp"); + auto minTemperature = std::get_if(&minTempVariant); + auto maxTemperature = std::get_if(&maxTempVariant); + if (minTemperature && maxTemperature) + { + // make sure the temperature range is between [0, 655.35] kelvin + Ogre::GpuProgramParametersSharedPtr params = + heatSignatureMaterial->getTechnique(0)->getPass(0)-> + getFragmentProgramParameters(); + params->setNamedConstant("minTemp", + std::max(static_cast(*minTemperature), 0.0f)); + params->setNamedConstant("maxTemp", + std::min(static_cast(*maxTemperature), 655.35f)); + } + heatSignatureMaterial->load(); + this->heatSignatureMaterials[item->getId()] = heatSignatureMaterial; + } + + for (unsigned int i = 0; i < item->getNumSubItems(); ++i) + { + Ogre::SubItem *subItem = item->getSubItem(i); + + Ogre::HlmsDatablock *datablock = subItem->getDatablock(); + this->datablockMap[subItem] = datablock; + + subItem->setMaterial(this->heatSignatureMaterials[item->getId()]); + } + } + // background objects + else + { + Ogre::Aabb aabb = item->getWorldAabbUpdated(); + Ogre::AxisAlignedBox box = Ogre::AxisAlignedBox(aabb.getMinimum(), + aabb.getMaximum()); + + // we will be converting rgb values to tempearture values in shaders + // but we want to make sure the object rgb values are not affected by + // lighting, so disable lighting + // Also check if objects are within camera view + if (ogreVisual->GeometryCount() > 0u && + this->ogreCamera->isVisible(box)) + { + auto geom = ogreVisual->GeometryByIndex(0); + if (geom) + { + MaterialPtr mat = geom->Material(); + Ogre2MaterialPtr ogreMat = + std::dynamic_pointer_cast(mat); + Ogre::HlmsUnlitDatablock *unlit = ogreMat->UnlitDatablock(); + for (unsigned int i = 0; i < item->getNumSubItems(); ++i) + { + Ogre::SubItem *subItem = item->getSubItem(i); + Ogre::HlmsDatablock *datablock = subItem->getDatablock(); + this->datablockMap[subItem] = datablock; + subItem->setDatablock(unlit); + } + } + } + } } itor.moveNext(); } @@ -242,7 +381,7 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( void Ogre2ThermalCameraMaterialSwitcher::postRenderTargetUpdate( const Ogre::RenderTargetEvent & /*_evt*/) { - // restore item to use hlms material + // restore item to use pbs hlms material for (auto it : this->datablockMap) { Ogre::SubItem *subItem = it.first; @@ -441,6 +580,8 @@ void Ogre2ThermalCamera::CreateThermalTexture() static_cast(this->ambientRange)); psParams->setNamedConstant("heatSourceTempRange", static_cast(this->heatSourceTempRange)); + psParams->setNamedConstant("rgbToTemp", + static_cast(this->dataPtr->rgbToTemp)); // Create thermal camera compositor auto engine = Ogre2RenderEngine::Instance(); @@ -455,17 +596,7 @@ void Ogre2ThermalCamera::CreateThermalTexture() // { // in 0 rt_input // texture depthTexture target_width target_height PF_D32_FLOAT - // texture colorTexture target_width target_height PF_R8G8B8 - // target depthTexture - // { - // pass clear - // { - // colour_value 0.0 0.0 0.0 1.0 - // } - // pass render_scene - // { - // } - // } + // texture colorTexture target_width target_height PF_R8G8B8A8 // target colorTexture // { // pass clear @@ -517,7 +648,9 @@ void Ogre2ThermalCamera::CreateThermalTexture() thermalTexDef->uav = false; thermalTexDef->automipmaps = false; thermalTexDef->hwGammaWrite = Ogre::TextureDefinitionBase::BoolFalse; - thermalTexDef->depthBufferId = Ogre::DepthBuffer::POOL_NON_SHAREABLE; + // set to default pool so that when the colorTexture pass is rendered, its + // depth data get populated to depthTexture + thermalTexDef->depthBufferId = Ogre::DepthBuffer::POOL_DEFAULT; thermalTexDef->depthBufferFormat = Ogre::PF_UNKNOWN; thermalTexDef->fsaaExplicitResolve = false; @@ -530,7 +663,7 @@ void Ogre2ThermalCamera::CreateThermalTexture() colorTexDef->numMipmaps = 0; colorTexDef->widthFactor = 1; colorTexDef->heightFactor = 1; - colorTexDef->formatList = {Ogre::PF_R8G8B8}; + colorTexDef->formatList = {Ogre::PF_R8G8B8A8}; colorTexDef->fsaa = 0; colorTexDef->uav = false; colorTexDef->automipmaps = false; @@ -540,24 +673,7 @@ void Ogre2ThermalCamera::CreateThermalTexture() colorTexDef->preferDepthTexture = true; colorTexDef->fsaaExplicitResolve = false; - nodeDef->setNumTargetPass(3); - Ogre::CompositorTargetDef *depthTargetDef = - nodeDef->addTargetPass("depthTexture"); - depthTargetDef->setNumPasses(2); - { - // clear pass - Ogre::CompositorPassClearDef *passClear = - static_cast( - depthTargetDef->addPass(Ogre::PASS_CLEAR)); - passClear->mColourValue = Ogre::ColourValue(this->FarClipPlane(), 0, 0); - // scene pass - Ogre::CompositorPassSceneDef *passScene = - static_cast( - depthTargetDef->addPass(Ogre::PASS_SCENE)); - passScene->mVisibilityMask = IGN_VISIBILITY_ALL - & ~(IGN_VISIBILITY_GUI | IGN_VISIBILITY_SELECTABLE); - } - + nodeDef->setNumTargetPass(2); Ogre::CompositorTargetDef *colorTargetDef = nodeDef->addTargetPass("colorTexture"); colorTargetDef->setNumPasses(2); @@ -568,14 +684,10 @@ void Ogre2ThermalCamera::CreateThermalTexture() colorTargetDef->addPass(Ogre::PASS_CLEAR)); passClear->mColourValue = Ogre::ColourValue(0, 0, 0); // scene pass - Ogre::CompositorPassSceneDef *passScene = - static_cast( - colorTargetDef->addPass(Ogre::PASS_SCENE)); - // set thermal camera custom visibility mask when rendering heat sources - passScene->mVisibilityMask = 0x10000000; + colorTargetDef->addPass(Ogre::PASS_SCENE); } - // rt_input target - converts depth to thermal + // rt_input target - converts to thermal Ogre::CompositorTargetDef *inputTargetDef = nodeDef->addTargetPass("rt_input"); inputTargetDef->setNumPasses(2); @@ -632,10 +744,10 @@ void Ogre2ThermalCamera::CreateThermalTexture() auto channels = node->getLocalTextures(); for (auto c : channels) { - if (c.textures[0]->getSrcFormat() == Ogre::PF_R8G8B8) + if (c.textures[0]->getSrcFormat() == Ogre::PF_R8G8B8A8) { this->dataPtr->thermalMaterialSwitcher.reset( - new Ogre2ThermalCameraMaterialSwitcher(this->scene)); + new Ogre2ThermalCameraMaterialSwitcher(this->scene, this->Name())); c.target->addListener(this->dataPtr->thermalMaterialSwitcher.get()); break; } @@ -699,14 +811,14 @@ void Ogre2ThermalCamera::PostRender() this->dataPtr->thermalImage, width, height, 1, "L16"); // Uncomment to debug thermal output - // igndbg << "wxh: " << width << " x " << height << std::endl; + // std::cout << "wxh: " << width << " x " << height << std::endl; // for (unsigned int i = 0; i < height; ++i) // { // for (unsigned int j = 0; j < width; ++j) // { - // igndbg << "[" << this->dataPtr->thermalImage[i*width + j] << "]"; + // std::cout << "[" << this->dataPtr->thermalImage[i*width + j] << "]"; // } - // igndbg << std::endl; + // std::cout << std::endl; // } } diff --git a/ogre2/src/media/materials/programs/heat_signature_fs.glsl b/ogre2/src/media/materials/programs/heat_signature_fs.glsl new file mode 100644 index 000000000..d01951e53 --- /dev/null +++ b/ogre2/src/media/materials/programs/heat_signature_fs.glsl @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2021 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#version 330 + +// The input texture, which is set up by the Ogre Compositor infrastructure. +uniform sampler2D RT; + +// input params from vertex shader +in block +{ + vec2 uv0; +} inPs; + +// final output color +out vec4 fragColor; + +// The minimum and maximum temprature values (in Kelvin) that the +// heat signature texture should be normalized to +// (users can override these defaults) +uniform float minTemp = 0.0; +uniform float maxTemp = 100.0; + +// map a temperature from the [0, 655.35] range to the [minTemp, maxTemp] +// range (655.35 is the largest Kelvin value allowed) +float mapNormalized(float num) +{ + float mappedKelvin = ((maxTemp - minTemp) * num) + minTemp; + return mappedKelvin / 655.35; +} + +void main() +{ + float heat = texture(RT, inPs.uv0.xy).x; + + // set g, b, a to 0. This will be used by thermal_camera_fs.glsl to determine + // if a particular fragment is a heat source or not + fragColor = vec4(mapNormalized(heat), 0, 0, 0.0); +} diff --git a/ogre2/src/media/materials/programs/thermal_camera_fs.glsl b/ogre2/src/media/materials/programs/thermal_camera_fs.glsl index e401e8eb6..561ba13cf 100644 --- a/ogre2/src/media/materials/programs/thermal_camera_fs.glsl +++ b/ogre2/src/media/materials/programs/thermal_camera_fs.glsl @@ -37,6 +37,7 @@ uniform float range; uniform float resolution; uniform float heatSourceTempRange; uniform float ambient; +uniform int rgbToTemp; float getDepth(vec2 uv) { @@ -51,28 +52,63 @@ void main() float temp = ambient; float heatRange = range; - // get depth - float d = getDepth(inPs.uv0); - - // reconstruct 3d viewspace pos from depth - vec3 viewSpacePos = inPs.cameraDir * d; - - d = -viewSpacePos.z; - d = (d-near) / (far-near); + // dNorm value is between [0, 1]. It is used to for varying temperature + // value of a fragment. + // When dNorm = 1, temp = temp + heatRange*0.5. + // When dNorm = 0, temp = temp - heatRange*0.5. + float dNorm = 0.5; // check for heat source - float heat = texture(colorTexture, inPs.uv0).x; + // heat source are objects with uniform temperature or heat signature + // The custom heat source / signature shaders stores heat data in + // a vec4 of [heat, 0, 0, 0] so we test to see if it is a heat + // source by checking gba == 0. This is more of a hack but the idea is to + // avoid having to render an extra pass to create a mask of heat source + // objects + vec4 rgba = texture(colorTexture, inPs.uv0).rgba; + bool isHeatSource = (rgba.g == 0.0 && rgba.b == 0.0 && rgba.a == 0.0); + float heat = rgba.r; + if (heat > 0.0) { - // heat is normalized so convert back to work in kelvin - temp = heat * 655.35; + if (isHeatSource) + { + // heat is normalized so convert back to work in kelvin + temp = heat * 655.35; + + // set temperature variation for heat source + heatRange = heatSourceTempRange; + } + else + { + // other non-heat source objects are assigned ambient temperature + temp = ambient; + } + } - // set temperature variation for heat source - heatRange = heatSourceTempRange; + // add temperature variation, either as a function of color or depth + if (rgbToTemp == 1) + { + if (heat > 0.0 && !isHeatSource) + { + // convert to grayscale: darker = warmer + // (https://docs.opencv.org/3.4/de/d25/imgproc_color_conversions.html) + float gray = rgba.r * 0.299 + rgba.g * 0.587 + rgba.b*0.114; + dNorm = 1.0 - gray; + } + } + else + { + // get depth + float d = getDepth(inPs.uv0); + // reconstruct 3d viewspace pos from depth + vec3 viewSpacePos = inPs.cameraDir * d; + d = -viewSpacePos.z; + dNorm = (d-near) / (far-near); } - // simulate temp variation as a function of depth - float delta = (1.0 - d) * heatRange; + // simulate temp variations + float delta = (1.0 - dNorm) * heatRange; temp = temp - heatRange / 2.0 + delta; clamp(temp, min, max); diff --git a/ogre2/src/media/materials/scripts/thermal.material b/ogre2/src/media/materials/scripts/thermal.material index 61929d1b1..eecc3f19a 100644 --- a/ogre2/src/media/materials/scripts/thermal.material +++ b/ogre2/src/media/materials/scripts/thermal.material @@ -98,3 +98,47 @@ material ThermalHeatSource } } } + +// copied from gaussian_noise.material +vertex_program HeatSignatureVS glsl +{ + source gaussian_noise_vs.glsl + default_params + { + param_named_auto worldViewProj worldviewproj_matrix + } +} + +fragment_program HeatSignatureFS glsl +{ + source heat_signature_fs.glsl + default_params + { + param_named RT int 0 + } +} + +material ThermalHeatSignature +{ + technique + { + pass + { + fog_override true + + // using gaussian noise VS because this is a simple VS that accomplishes + // what we need for a heat signature VS + vertex_program_ref HeatSignatureVS { } + + fragment_program_ref HeatSignatureFS { } + + texture_unit RT + { + tex_coord_set 0 + + // the texture for this texture unit is set programmatically + // since the texture file location and name are specified by the user + } + } + } +} diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index 1ce399c9a..4c0e72b94 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -53,8 +53,16 @@ void OnNewThermalFrame(uint16_t *_scanDest, const uint16_t *_scan, class ThermalCameraTest: public testing::Test, public testing::WithParamInterface { - // Create a Camera sensor from a SDF and gets a image message - public: void ThermalCameraBoxes(const std::string &_renderEngine); + // Create a Camera sensor from a SDF and gets a image message. + // If _useHeatSignature is false, uniform surface temperature is tested + // (if _useHeatSignature is true, applying a heat signature is tested) + public: void ThermalCameraBoxes(const std::string &_renderEngine, + const bool _useHeatSignature); + + // Path to test textures + public: const std::string TEST_MEDIA_PATH = + ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), + "test", "media", "materials", "textures"); // Documentation inherited protected: void SetUp() override @@ -65,7 +73,7 @@ class ThermalCameraTest: public testing::Test, ////////////////////////////////////////////////// void ThermalCameraTest::ThermalCameraBoxes( - const std::string &_renderEngine) + const std::string &_renderEngine, const bool _useHeatSignature) { int imgWidth = 50; int imgHeight = 50; @@ -81,6 +89,13 @@ void ThermalCameraTest::ThermalCameraBoxes( << "' doesn't support thermal cameras" << std::endl; return; } + // Only ogre2 supports heat signatures + else if (_useHeatSignature && (_renderEngine.compare("ogre2") != 0)) + { + igndbg << "Engine '" << _renderEngine + << "' doesn't support heat signatures" << std::endl; + return; + } // Setup ign-rendering with an empty scene auto *engine = ignition::rendering::engine(_renderEngine); @@ -111,6 +126,17 @@ void ThermalCameraTest::ThermalCameraBoxes( // set box temperature float boxTemp = 310.0; box->SetUserData("temperature", boxTemp); + if (_useHeatSignature) + { + std::string textureName = + ignition::common::joinPaths(TEST_MEDIA_PATH, "gray_texture.png"); + box->SetUserData("temperature", textureName); + box->SetUserData("minTemp", 100.0f); + box->SetUserData("maxTemp", 200.0f); + // (the heat signature is just a texture of gray pixels, + // so the box's temperature should be midway between minTemp and maxTemp) + boxTemp = 150.0f; + } root->AddChild(box); { @@ -230,9 +256,14 @@ void ThermalCameraTest::ThermalCameraBoxes( ignition::rendering::unloadEngine(engine->Name()); } -TEST_P(ThermalCameraTest, ThermalCameraBoxes) +TEST_P(ThermalCameraTest, ThermalCameraBoxesUniformTemp) +{ + ThermalCameraBoxes(GetParam(), false); +} + +TEST_P(ThermalCameraTest, ThermalCameraBoxesHeatSignature) { - ThermalCameraBoxes(GetParam()); + ThermalCameraBoxes(GetParam(), true); } INSTANTIATE_TEST_CASE_P(ThermalCamera, ThermalCameraTest, diff --git a/test/media/materials/textures/gray_texture.png b/test/media/materials/textures/gray_texture.png new file mode 100644 index 000000000..466d2009e Binary files /dev/null and b/test/media/materials/textures/gray_texture.png differ