Skip to content

Commit 55fb3c5

Browse files
authored
Fix user settings of thermal camera being ignored (#1138)
Fixes #1134 Changes to thermal camera settings that can be made through the plugin gz-sim-thermal-sensor-system would not show up in the result. While the value of the data members was updated, the named constants in the material shader used for rendering were not. We fix that by always setting the shader constants in PreRender to the current values. This might be relevant for other thermal camera settings as well, but this focuses on min and max temperature and resolution, as those can be modified through the gz-sim-thermal-sensor-system plugin. --------- Signed-off-by: Marcel Jacobse <[email protected]>
1 parent 2fa760b commit 55fb3c5

File tree

2 files changed

+225
-0
lines changed

2 files changed

+225
-0
lines changed

ogre2/src/Ogre2ThermalCamera.cc

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1120,6 +1120,21 @@ void Ogre2ThermalCamera::PreRender()
11201120
if (!this->dataPtr->ogreThermalTexture)
11211121
this->CreateThermalTexture();
11221122

1123+
// ensure that certain shader constants are up-to-date so that changes that
1124+
// users can make to the settings show up in the thermal result immediately
1125+
Ogre::Pass *pass =
1126+
this->dataPtr->thermalMaterial->getTechnique(0)->getPass(0);
1127+
Ogre::GpuProgramParametersSharedPtr psParams =
1128+
pass->getFragmentProgramParameters();
1129+
psParams->setNamedConstant("max",
1130+
static_cast<float>(this->maxTemp));
1131+
psParams->setNamedConstant("min",
1132+
static_cast<float>(this->minTemp));
1133+
psParams->setNamedConstant("resolution",
1134+
static_cast<float>(this->resolution));
1135+
1136+
this->dataPtr->thermalMaterialSwitcher->SetLinearResolution(this->resolution);
1137+
11231138
// todo(iche033) Override BaseCamera::SetProjectionMatrix() function in
11241139
// main / gz-rendering9 instead of checking and setting the custom
11251140
// projection matrix here

test/integration/thermal_camera.cc

Lines changed: 210 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -818,3 +818,213 @@ TEST_F(ThermalCameraTest, ThermalCameraMaxTemperatureIsClamped)
818818

819819
engine->DestroyScene(scene);
820820
}
821+
822+
//////////////////////////////////////////////////
823+
TEST_F(ThermalCameraTest, ThermalCameraMinTemperatureUpdate)
824+
{
825+
// Updating the min temperature currently only works with Ogre2
826+
CHECK_SUPPORTED_ENGINE("ogre2");
827+
828+
const unsigned int imgWidth = 50;
829+
const unsigned int imgHeight = 50;
830+
831+
gz::rendering::ScenePtr scene = engine->CreateScene("scene");
832+
833+
{
834+
// Create thermal camera
835+
auto thermalCamera = scene->CreateThermalCamera("ThermalCamera");
836+
ASSERT_NE(thermalCamera, nullptr);
837+
838+
// Configure thermal camera
839+
thermalCamera->SetImageWidth(imgWidth);
840+
EXPECT_EQ(thermalCamera->ImageWidth(), imgWidth);
841+
thermalCamera->SetImageHeight(imgHeight);
842+
EXPECT_EQ(thermalCamera->ImageHeight(), imgHeight);
843+
844+
scene->RootVisual()->AddChild(thermalCamera);
845+
846+
// Set a callback on the camera sensor to get a thermal camera frame
847+
std::vector<uint16_t> thermalData(imgHeight * imgWidth);
848+
gz::common::ConnectionPtr connection =
849+
thermalCamera->ConnectNewThermalFrame(
850+
std::bind(&::OnNewThermalFrame, thermalData.data(),
851+
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
852+
std::placeholders::_4, std::placeholders::_5));
853+
EXPECT_NE(nullptr, connection);
854+
855+
const float linearResolution = 0.01f;
856+
thermalCamera->SetLinearResolution(linearResolution);
857+
EXPECT_FLOAT_EQ(linearResolution, thermalCamera->LinearResolution());
858+
859+
// set a minimum temperature and a smaller ambient temperature
860+
const float minTemp = 100.0f;
861+
const float ambientTemp = 50.0f;
862+
thermalCamera->SetMinTemperature(minTemp);
863+
EXPECT_FLOAT_EQ(minTemp, thermalCamera->MinTemperature());
864+
thermalCamera->SetAmbientTemperature(ambientTemp);
865+
EXPECT_FLOAT_EQ(ambientTemp, thermalCamera->AmbientTemperature());
866+
867+
// Update once to create image
868+
thermalCamera->Update();
869+
870+
for (const uint16_t value : thermalData) {
871+
const float temp = static_cast<float>(value) * linearResolution;
872+
EXPECT_NEAR(temp, minTemp, linearResolution);
873+
}
874+
875+
// set new minimum temperature
876+
const float newMinTemp = 150.0f;
877+
thermalCamera->SetMinTemperature(newMinTemp);
878+
thermalCamera->Update();
879+
880+
// check that new minimum temperature is applied
881+
for (const uint16_t value : thermalData) {
882+
const float temp = static_cast<float>(value) * linearResolution;
883+
EXPECT_NEAR(temp, newMinTemp, linearResolution);
884+
}
885+
886+
// Clean up
887+
connection.reset();
888+
}
889+
890+
engine->DestroyScene(scene);
891+
}
892+
893+
//////////////////////////////////////////////////
894+
TEST_F(ThermalCameraTest, ThermalCameraMaxTemperatureUpdate)
895+
{
896+
// Updating the max temperature currently only works with Ogre2
897+
CHECK_SUPPORTED_ENGINE("ogre2");
898+
899+
const unsigned int imgWidth = 50;
900+
const unsigned int imgHeight = 50;
901+
902+
gz::rendering::ScenePtr scene = engine->CreateScene("scene");
903+
904+
{
905+
// Create thermal camera
906+
auto thermalCamera = scene->CreateThermalCamera("ThermalCamera");
907+
ASSERT_NE(thermalCamera, nullptr);
908+
909+
// Configure thermal camera
910+
thermalCamera->SetImageWidth(imgWidth);
911+
EXPECT_EQ(thermalCamera->ImageWidth(), imgWidth);
912+
thermalCamera->SetImageHeight(imgHeight);
913+
EXPECT_EQ(thermalCamera->ImageHeight(), imgHeight);
914+
915+
scene->RootVisual()->AddChild(thermalCamera);
916+
917+
// Set a callback on the camera sensor to get a thermal camera frame
918+
std::vector<uint16_t> thermalData(imgHeight * imgWidth);
919+
gz::common::ConnectionPtr connection =
920+
thermalCamera->ConnectNewThermalFrame(
921+
std::bind(&::OnNewThermalFrame, thermalData.data(),
922+
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
923+
std::placeholders::_4, std::placeholders::_5));
924+
EXPECT_NE(nullptr, connection);
925+
926+
const float linearResolution = 0.01f;
927+
thermalCamera->SetLinearResolution(linearResolution);
928+
EXPECT_FLOAT_EQ(linearResolution, thermalCamera->LinearResolution());
929+
930+
// set a maximum temperature and a greater ambient temperature
931+
const float maxTemp = 500.0f;
932+
const float ambientTemp = 550.0f;
933+
thermalCamera->SetMaxTemperature(maxTemp);
934+
EXPECT_FLOAT_EQ(maxTemp, thermalCamera->MaxTemperature());
935+
thermalCamera->SetAmbientTemperature(ambientTemp);
936+
EXPECT_FLOAT_EQ(ambientTemp, thermalCamera->AmbientTemperature());
937+
938+
// Update once to create image
939+
thermalCamera->Update();
940+
941+
for (const uint16_t value : thermalData) {
942+
const float temp = static_cast<float>(value) * linearResolution;
943+
EXPECT_NEAR(temp, maxTemp, linearResolution);
944+
}
945+
946+
// set new maximum temperature
947+
const float newMaxTemp = 525.0f;
948+
thermalCamera->SetMaxTemperature(newMaxTemp);
949+
thermalCamera->Update();
950+
951+
// check that new maximum temperature is applied
952+
for (const uint16_t value : thermalData) {
953+
const float temp = static_cast<float>(value) * linearResolution;
954+
EXPECT_NEAR(temp, newMaxTemp, linearResolution);
955+
}
956+
957+
// Clean up
958+
connection.reset();
959+
}
960+
961+
engine->DestroyScene(scene);
962+
}
963+
964+
//////////////////////////////////////////////////
965+
TEST_F(ThermalCameraTest, ThermalCameraResolutionUpdate)
966+
{
967+
// Updating the resolution currently only works with Ogre2
968+
CHECK_SUPPORTED_ENGINE("ogre2");
969+
970+
const unsigned int imgWidth = 50;
971+
const unsigned int imgHeight = 50;
972+
973+
gz::rendering::ScenePtr scene = engine->CreateScene("scene");
974+
975+
{
976+
// Create thermal camera
977+
auto thermalCamera = scene->CreateThermalCamera("ThermalCamera");
978+
ASSERT_NE(thermalCamera, nullptr);
979+
980+
// Configure thermal camera
981+
thermalCamera->SetImageWidth(imgWidth);
982+
EXPECT_EQ(thermalCamera->ImageWidth(), imgWidth);
983+
thermalCamera->SetImageHeight(imgHeight);
984+
EXPECT_EQ(thermalCamera->ImageHeight(), imgHeight);
985+
986+
scene->RootVisual()->AddChild(thermalCamera);
987+
988+
// Set a callback on the camera sensor to get a thermal camera frame
989+
std::vector<uint16_t> thermalData(imgHeight * imgWidth);
990+
gz::common::ConnectionPtr connection =
991+
thermalCamera->ConnectNewThermalFrame(
992+
std::bind(&::OnNewThermalFrame, thermalData.data(),
993+
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
994+
std::placeholders::_4, std::placeholders::_5));
995+
EXPECT_NE(nullptr, connection);
996+
997+
const float ambientTemp = 300.0f;
998+
thermalCamera->SetAmbientTemperature(ambientTemp);
999+
EXPECT_FLOAT_EQ(ambientTemp, thermalCamera->AmbientTemperature());
1000+
1001+
const float linearResolution = 0.01f;
1002+
thermalCamera->SetLinearResolution(linearResolution);
1003+
EXPECT_FLOAT_EQ(linearResolution, thermalCamera->LinearResolution());
1004+
1005+
// Update once to create image
1006+
thermalCamera->Update();
1007+
1008+
// check result with initial resolution
1009+
for (const uint16_t value : thermalData) {
1010+
const float temp = static_cast<float>(value) * linearResolution;
1011+
EXPECT_NEAR(temp, ambientTemp, linearResolution);
1012+
}
1013+
1014+
// set new resolution
1015+
const float newLinearResolution = 0.02f;
1016+
thermalCamera->SetLinearResolution(newLinearResolution);
1017+
thermalCamera->Update();
1018+
1019+
// check that camera has applied the new resolution
1020+
for (const uint16_t value : thermalData) {
1021+
const float temp = static_cast<float>(value) * newLinearResolution;
1022+
EXPECT_NEAR(temp, ambientTemp, newLinearResolution);
1023+
}
1024+
1025+
// Clean up
1026+
connection.reset();
1027+
}
1028+
1029+
engine->DestroyScene(scene);
1030+
}

0 commit comments

Comments
 (0)