Skip to content

Commit e3105a3

Browse files
Fix clamp of temperature in thermal camera output (#1133) (#1136)
The minimum and maximum temperature of the thermal camera were not applied properly. clamp was called in the shader without using the result. This also adds simple test cases that allow easily reproducing the bug before this change. --------- (cherry picked from commit 2fa760b) Signed-off-by: Marcel Jacobse <[email protected]> Co-authored-by: Marcel Jacobse <[email protected]>
1 parent 72a82eb commit e3105a3

File tree

4 files changed

+119
-3
lines changed

4 files changed

+119
-3
lines changed

ogre/src/media/materials/programs/thermal_camera_fs.glsl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@ void main()
5050
// simulate temp variation as a function of depth
5151
float delta = (1.0 - d) * heatRange;
5252
temp = temp - heatRange / 2.0 + delta;
53-
clamp(temp, min, max);
53+
temp = clamp(temp, min, max);
5454

5555
// apply resolution factor
5656
temp /= resolution;

ogre2/src/media/materials/programs/GLSL/thermal_camera_fs.glsl

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,7 @@ void main()
117117
// simulate temp variations
118118
float delta = (1.0 - dNorm) * heatRange;
119119
temp = temp - heatRange / 2.0 + delta;
120-
clamp(temp, min, max);
120+
temp = clamp(temp, min, max);
121121

122122
// apply resolution factor
123123
temp /= resolution;

ogre2/src/media/materials/programs/Metal/thermal_camera_fs.metal

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ fragment float4 main_metal
124124
// simulate temp variations
125125
float delta = (1.0 - dNorm) * heatRange;
126126
temp = temp - heatRange / 2.0 + delta;
127-
clamp(temp, p.min, p.max);
127+
temp = clamp(temp, p.min, p.max);
128128

129129
// apply resolution factor
130130
temp /= p.resolution;

test/integration/thermal_camera.cc

Lines changed: 116 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,8 @@
1919

2020
#include "CommonRenderingTest.hh"
2121

22+
#include <vector>
23+
2224
#include <gz/common/Filesystem.hh>
2325
#include <gz/common/Event.hh>
2426

@@ -702,3 +704,117 @@ TEST_F(ThermalCameraTest, ThermalCameraParticles)
702704

703705
engine->DestroyScene(scene);
704706
}
707+
708+
//////////////////////////////////////////////////
709+
TEST_F(ThermalCameraTest, ThermalCameraMinTemperatureIsClamped)
710+
{
711+
const unsigned int imgWidth = 50;
712+
const unsigned int imgHeight = 50;
713+
714+
gz::rendering::ScenePtr scene = engine->CreateScene("scene");
715+
716+
{
717+
// Create thermal camera
718+
auto thermalCamera = scene->CreateThermalCamera("ThermalCamera");
719+
ASSERT_NE(thermalCamera, nullptr);
720+
721+
// Configure thermal camera
722+
thermalCamera->SetImageWidth(imgWidth);
723+
EXPECT_EQ(thermalCamera->ImageWidth(), imgWidth);
724+
thermalCamera->SetImageHeight(imgHeight);
725+
EXPECT_EQ(thermalCamera->ImageHeight(), imgHeight);
726+
727+
scene->RootVisual()->AddChild(thermalCamera);
728+
729+
// Set a callback on the camera sensor to get a thermal camera frame
730+
std::vector<uint16_t> thermalData(imgHeight * imgWidth);
731+
gz::common::ConnectionPtr connection =
732+
thermalCamera->ConnectNewThermalFrame(
733+
std::bind(&::OnNewThermalFrame, thermalData.data(),
734+
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
735+
std::placeholders::_4, std::placeholders::_5));
736+
EXPECT_NE(nullptr, connection);
737+
738+
const float linearResolution = 0.01f;
739+
thermalCamera->SetLinearResolution(linearResolution);
740+
EXPECT_FLOAT_EQ(linearResolution, thermalCamera->LinearResolution());
741+
742+
// set a minimum temperature and a smaller ambient temperature
743+
const float minTemp = 100.0f;
744+
const float ambientTemp = 50.0f;
745+
thermalCamera->SetMinTemperature(minTemp);
746+
EXPECT_FLOAT_EQ(minTemp, thermalCamera->MinTemperature());
747+
thermalCamera->SetAmbientTemperature(ambientTemp);
748+
EXPECT_FLOAT_EQ(ambientTemp, thermalCamera->AmbientTemperature());
749+
750+
// Update once to create image
751+
thermalCamera->Update();
752+
753+
for (const uint16_t value : thermalData) {
754+
const float temp = static_cast<float>(value) * linearResolution;
755+
EXPECT_NEAR(temp, minTemp, linearResolution);
756+
}
757+
758+
// Clean up
759+
connection.reset();
760+
}
761+
762+
engine->DestroyScene(scene);
763+
}
764+
765+
//////////////////////////////////////////////////
766+
TEST_F(ThermalCameraTest, ThermalCameraMaxTemperatureIsClamped)
767+
{
768+
const unsigned int imgWidth = 50;
769+
const unsigned int imgHeight = 50;
770+
771+
gz::rendering::ScenePtr scene = engine->CreateScene("scene");
772+
773+
{
774+
// Create thermal camera
775+
auto thermalCamera = scene->CreateThermalCamera("ThermalCamera");
776+
ASSERT_NE(thermalCamera, nullptr);
777+
778+
// Configure thermal camera
779+
thermalCamera->SetImageWidth(imgWidth);
780+
EXPECT_EQ(thermalCamera->ImageWidth(), imgWidth);
781+
thermalCamera->SetImageHeight(imgHeight);
782+
EXPECT_EQ(thermalCamera->ImageHeight(), imgHeight);
783+
784+
scene->RootVisual()->AddChild(thermalCamera);
785+
786+
// Set a callback on the camera sensor to get a thermal camera frame
787+
std::vector<uint16_t> thermalData(imgHeight * imgWidth);
788+
gz::common::ConnectionPtr connection =
789+
thermalCamera->ConnectNewThermalFrame(
790+
std::bind(&::OnNewThermalFrame, thermalData.data(),
791+
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
792+
std::placeholders::_4, std::placeholders::_5));
793+
EXPECT_NE(nullptr, connection);
794+
795+
const float linearResolution = 0.01f;
796+
thermalCamera->SetLinearResolution(linearResolution);
797+
EXPECT_FLOAT_EQ(linearResolution, thermalCamera->LinearResolution());
798+
799+
// set a maximum temperature and a greater ambient temperature
800+
const float maxTemp = 500.0f;
801+
const float ambientTemp = 550.0f;
802+
thermalCamera->SetMaxTemperature(maxTemp);
803+
EXPECT_FLOAT_EQ(maxTemp, thermalCamera->MaxTemperature());
804+
thermalCamera->SetAmbientTemperature(ambientTemp);
805+
EXPECT_FLOAT_EQ(ambientTemp, thermalCamera->AmbientTemperature());
806+
807+
// Update once to create image
808+
thermalCamera->Update();
809+
810+
for (const uint16_t value : thermalData) {
811+
const float temp = static_cast<float>(value) * linearResolution;
812+
EXPECT_NEAR(temp, maxTemp, linearResolution);
813+
}
814+
815+
// Clean up
816+
connection.reset();
817+
}
818+
819+
engine->DestroyScene(scene);
820+
}

0 commit comments

Comments
 (0)