Skip to content

Commit

Permalink
Add temperature variations to thermal camera readings based on color (#…
Browse files Browse the repository at this point in the history
…211)

* vary non-heat source temp based on rgb balues

Signed-off-by: Ian Chen <[email protected]>

* add more comments, var to set rgb to temp

Signed-off-by: Ian Chen <[email protected]>

* add more doc

Signed-off-by: Ian Chen <[email protected]>

* remove comment

Signed-off-by: Ian Chen <[email protected]>

* feedback changes

Signed-off-by: Ian Chen <[email protected]>

* added reference link to RGB/grayscale equation

Signed-off-by: Ashton Larkin <[email protected]>

Co-authored-by: Ashton Larkin <[email protected]>
  • Loading branch information
iche033 and adlarkin authored Jan 26, 2021
1 parent df3024d commit 7f5a9fb
Show file tree
Hide file tree
Showing 5 changed files with 143 additions and 77 deletions.
6 changes: 6 additions & 0 deletions ogre2/include/ignition/rendering/ogre2/Ogre2Material.hh
Original file line number Diff line number Diff line change
Expand Up @@ -199,6 +199,12 @@ namespace ignition
// Documentation inherited
public: virtual void SetDepthWriteEnabled(bool _enabled) override;

/// \brief Helper function to convert an ogre Pbs datablck to Unlit datablock
/// \param[in] _in Input pbs datablock
/// \param[out] _out Output unlit datablock
public: static void PbsToUnlitDatablock(Ogre::HlmsPbsDatablock *_in,
Ogre::HlmsUnlitDatablock *_out);

/// \brief Set the texture map for this material
/// \param[in] _texture Name of the texture.
/// \param[in] _type Type of texture, i.e. diffuse, normal, roughness,
Expand Down
29 changes: 17 additions & 12 deletions ogre2/src/Ogre2Material.cc
Original file line number Diff line number Diff line change
Expand Up @@ -579,18 +579,23 @@ Ogre::HlmsUnlitDatablock *Ogre2Material::UnlitDatablock()
void Ogre2Material::FillUnlitDatablock(Ogre::HlmsUnlitDatablock *_datablock)
const
{
auto tex = this->ogreDatablock->getTexture(Ogre::PBSM_DIFFUSE);
PbsToUnlitDatablock(this->ogreDatablock, _datablock);
}

//////////////////////////////////////////////////
void Ogre2Material::PbsToUnlitDatablock(Ogre::HlmsPbsDatablock *_in,
Ogre::HlmsUnlitDatablock *_out)
{
auto tex = _in->getTexture(Ogre::PBSM_DIFFUSE);
if (tex)
_datablock->setTexture(0, 0, tex);
auto samplerblock = this->ogreDatablock->getSamplerblock(Ogre::PBSM_DIFFUSE);
_out->setTexture(0, 0, tex);
auto samplerblock = _in->getSamplerblock(Ogre::PBSM_DIFFUSE);
if (samplerblock)
_datablock->setSamplerblock(0, *samplerblock);
_datablock->setMacroblock(
this->ogreDatablock->getMacroblock());
_datablock->setBlendblock(
this->ogreDatablock->getBlendblock());

_datablock->setUseColour(true);
Ogre::Vector3 c = this->ogreDatablock->getDiffuse();
_datablock->setColour(Ogre::ColourValue(c.x, c.y, c.z));
_out->setSamplerblock(0, *samplerblock);
_out->setMacroblock(_in->getMacroblock());
_out->setBlendblock(_in->getBlendblock());

_out->setUseColour(true);
Ogre::Vector3 c = _in->getDiffuse();
_out->setColour(Ogre::ColourValue(c.x, c.y, c.z));
}
114 changes: 65 additions & 49 deletions ogre2/src/Ogre2ThermalCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,17 @@
#include <unordered_map>
#include <variant>

#include <Hlms/Pbs/OgreHlmsPbsDatablock.h>
#include <Hlms/Unlit/OgreHlmsUnlitDatablock.h>

#include <ignition/common/Console.hh>
#include <ignition/common/Filesystem.hh>
#include <ignition/math/Helpers.hh>

#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"
Expand Down Expand Up @@ -95,13 +99,17 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener
/// \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<Ogre::SubItem *, Ogre::HlmsDatablock *> datablockMap;
private: std::unordered_map<Ogre::SubItem *, Ogre::HlmsDatablock *>
datablockMap;
};
}
}
Expand Down Expand Up @@ -150,6 +158,11 @@ class ignition::rendering::Ogre2ThermalCameraPrivate
/// \brief Pointer to material switcher
public: std::unique_ptr<Ogre2ThermalCameraMaterialSwitcher>
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;
Expand All @@ -171,6 +184,8 @@ Ogre2ThermalCameraMaterialSwitcher::Ogre2ThermalCameraMaterialSwitcher(

this->baseHeatSigMaterial = Ogre::MaterialManager::getSingleton().
getByName("ThermalHeatSignature");

this->ogreCamera = this->scene->OgreSceneManager()->findCamera(this->name);
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -237,8 +252,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);
Expand All @@ -247,8 +260,12 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate(
// normalize temperature value
float color = temp * 100.0 /
static_cast<float>(std::numeric_limits<uint16_t>::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;
Expand Down Expand Up @@ -340,9 +357,6 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate(
this->heatSignatureMaterials[item->getId()] = heatSignatureMaterial;
}

// 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);
Expand All @@ -353,6 +367,35 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate(
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<Ogre2Material>(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();
}
Expand All @@ -362,7 +405,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;
Expand Down Expand Up @@ -561,6 +604,8 @@ void Ogre2ThermalCamera::CreateThermalTexture()
static_cast<float>(this->ambientRange));
psParams->setNamedConstant("heatSourceTempRange",
static_cast<float>(this->heatSourceTempRange));
psParams->setNamedConstant("rgbToTemp",
static_cast<int>(this->dataPtr->rgbToTemp));

// Create thermal camera compositor
auto engine = Ogre2RenderEngine::Instance();
Expand All @@ -575,17 +620,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
Expand Down Expand Up @@ -637,7 +672,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;

Expand All @@ -650,7 +687,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;
Expand All @@ -660,24 +697,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<Ogre::CompositorPassClearDef *>(
depthTargetDef->addPass(Ogre::PASS_CLEAR));
passClear->mColourValue = Ogre::ColourValue(this->FarClipPlane(), 0, 0);
// scene pass
Ogre::CompositorPassSceneDef *passScene =
static_cast<Ogre::CompositorPassSceneDef *>(
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);
Expand All @@ -688,14 +708,10 @@ void Ogre2ThermalCamera::CreateThermalTexture()
colorTargetDef->addPass(Ogre::PASS_CLEAR));
passClear->mColourValue = Ogre::ColourValue(0, 0, 0);
// scene pass
Ogre::CompositorPassSceneDef *passScene =
static_cast<Ogre::CompositorPassSceneDef *>(
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);
Expand Down Expand Up @@ -752,7 +768,7 @@ 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, this->Name()));
Expand Down Expand Up @@ -819,14 +835,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;
// }
}

Expand Down
5 changes: 4 additions & 1 deletion ogre2/src/media/materials/programs/heat_signature_fs.glsl
Original file line number Diff line number Diff line change
Expand Up @@ -46,5 +46,8 @@ float mapNormalized(float num)
void main()
{
float heat = texture(RT, inPs.uv0.xy).x;
fragColor = vec4(mapNormalized(heat), 0, 0, 1.0);

// 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);
}
66 changes: 51 additions & 15 deletions ogre2/src/media/materials/programs/thermal_camera_fs.glsl
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ uniform float range;
uniform float resolution;
uniform float heatSourceTempRange;
uniform float ambient;
uniform int rgbToTemp;

float getDepth(vec2 uv)
{
Expand All @@ -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);

Expand Down

0 comments on commit 7f5a9fb

Please sign in to comment.