Skip to content

Commit 7d311d9

Browse files
mjacobseiche033
authored andcommitted
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]> (cherry picked from commit 55fb3c5) Signed-off-by: Ian Chen <[email protected]> # Conflicts: # ogre2/src/Ogre2ThermalCamera.cc
1 parent ff4cb13 commit 7d311d9

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
@@ -1119,6 +1119,21 @@ void Ogre2ThermalCamera::PreRender()
11191119
{
11201120
if (!this->dataPtr->ogreThermalTexture)
11211121
this->CreateThermalTexture();
1122+
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);
11221137
}
11231138

11241139
//////////////////////////////////////////////////

test/integration/thermal_camera.cc

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

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

0 commit comments

Comments
 (0)