From ca342de951998d382bd571b2a532b5d1781588fa Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 4 Feb 2021 23:11:09 -0800 Subject: [PATCH 1/9] add support for 8 bit thermal camera Signed-off-by: Ian Chen --- ogre2/src/Ogre2ThermalCamera.cc | 117 ++++++++-- .../materials/programs/heat_signature_fs.glsl | 8 +- .../materials/programs/thermal_camera_fs.glsl | 9 +- test/integration/thermal_camera.cc | 200 +++++++++++++++++- 4 files changed, 306 insertions(+), 28 deletions(-) diff --git a/ogre2/src/Ogre2ThermalCamera.cc b/ogre2/src/Ogre2ThermalCamera.cc index 1d5f36302..a65940051 100644 --- a/ogre2/src/Ogre2ThermalCamera.cc +++ b/ogre2/src/Ogre2ThermalCamera.cc @@ -75,6 +75,13 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener /// \brief destructor public: ~Ogre2ThermalCameraMaterialSwitcher() = default; + /// \brief Set image format + /// \param[in] _format Inage format + public: void SetFormat(PixelFormat _format); + + /// \brieft Set linear resolution + public: void SetLinearResolution(double _resolution); + /// \brief Callback when a render target is about to be rendered /// \param[in] _evt Ogre render target event containing information about /// the source render target. @@ -119,6 +126,15 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener /// \brief A map of ogre sub item pointer to their original hlms material private: std::unordered_map datablockMap; + + /// \brief linear temperature resolution. Defaults to 10mK + private: double resolution = 0.01; + + /// \brief thermal camera image format + private: PixelFormat format = PF_L16; + + /// \brief thermal camera image format + private: int bitDepth = 16u; }; } } @@ -130,7 +146,7 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener class ignition::rendering::Ogre2ThermalCameraPrivate { /// \brief The thermal buffer - public: uint16_t *thermalBuffer = nullptr; + public: unsigned char *thermalBuffer = nullptr; /// \brief Outgoing thermal data, used by newThermalFrame event. public: uint16_t *thermalImage = nullptr; @@ -172,6 +188,9 @@ class ignition::rendering::Ogre2ThermalCameraPrivate /// This only affects objects that are not heat sources /// TODO(anyone) add API for setting this value? public: bool rgbToTemp = true; + + /// \brief bit depth of each pixel + public: unsigned int bitDepth = 16u; }; using namespace ignition; @@ -196,6 +215,18 @@ Ogre2ThermalCameraMaterialSwitcher::Ogre2ThermalCameraMaterialSwitcher( this->ogreCamera = this->scene->OgreSceneManager()->findCamera(this->name); } +////////////////////////////////////////////////// +void Ogre2ThermalCameraMaterialSwitcher::SetFormat(PixelFormat _format) +{ + this->format = _format; + this->bitDepth = 8u * PixelUtil::BytesPerChannel(format); +} + +////////////////////////////////////////////////// +void Ogre2ThermalCameraMaterialSwitcher::SetLinearResolution(double _resolution) +{ + this->resolution = _resolution; +} ////////////////////////////////////////////////// void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( const Ogre::RenderTargetEvent & /*_evt*/) @@ -263,18 +294,14 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( for (unsigned int i = 0; i < item->getNumSubItems(); ++i) { Ogre::SubItem *subItem = item->getSubItem(i); - if (!subItem->hasCustomParameter(this->customParamIdx)) - { - // 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, 0, 0, 0.0)); - } + // normalize temperature value + float color = (temp / this->resolution) / ((1 << bitDepth) - 1.0); + + // 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, 0, 0, 0.0)); Ogre::HlmsDatablock *datablock = subItem->getDatablock(); this->datablockMap[subItem] = datablock; @@ -319,13 +346,18 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( if (minTemperature && maxTemperature) { // make sure the temperature range is between [0, 655.35] kelvin + // for 16 bit format and 10mK resolution + float maxTemp = ((1 << bitDepth) - 1.0) * this->resolution; 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)); + std::min(static_cast(*maxTemperature), maxTemp)); + params->setNamedConstant("bitDepth", this->bitDepth); + params->setNamedConstant("resolution", + static_cast(this->resolution)); } heatSignatureMaterial->load(); this->heatSignatureMaterials[item->getId()] = heatSignatureMaterial; @@ -552,6 +584,22 @@ void Ogre2ThermalCamera::CreateThermalTexture() this->ogreCamera->setNearClipDistance(nearPlane); this->ogreCamera->setFarClipDistance(farPlane); + // only support 8 bit and 16 bit formats for now. + // default to 16 bit + Ogre::PixelFormat ogrePF; + if (this->ImageFormat() == PF_L8) + { + ogrePF = Ogre::PF_L8; + } + else + { + this->SetImageFormat(PF_L16); + ogrePF = Ogre::PF_L16; + } + + PixelFormat format = this->ImageFormat(); + this->dataPtr->bitDepth = 8u * PixelUtil::BytesPerChannel(format); + // Set the uniform variables (thermal_camera_fs.glsl). // The projectParams is used to linearize thermal buffer data // The other params are used to clamp the range output @@ -582,6 +630,8 @@ void Ogre2ThermalCamera::CreateThermalTexture() static_cast(this->heatSourceTempRange)); psParams->setNamedConstant("rgbToTemp", static_cast(this->dataPtr->rgbToTemp)); + psParams->setNamedConstant("bitDepth", + static_cast(this->dataPtr->bitDepth)); // Create thermal camera compositor auto engine = Ogre2RenderEngine::Instance(); @@ -726,7 +776,7 @@ void Ogre2ThermalCamera::CreateThermalTexture() Ogre::TextureManager::getSingleton().createManual( this->Name() + "_thermal", "General", Ogre::TEX_TYPE_2D, this->ImageWidth(), this->ImageHeight(), 1, 0, - Ogre::PF_L16, Ogre::TU_RENDERTARGET, + ogrePF, Ogre::TU_RENDERTARGET, 0, false, 0, Ogre::BLANKSTRING, false, true); Ogre::RenderTarget *rt = @@ -748,6 +798,9 @@ void Ogre2ThermalCamera::CreateThermalTexture() { this->dataPtr->thermalMaterialSwitcher.reset( new Ogre2ThermalCameraMaterialSwitcher(this->scene, this->Name())); + this->dataPtr->thermalMaterialSwitcher->SetFormat(this->ImageFormat()); + this->dataPtr->thermalMaterialSwitcher->SetLinearResolution( + this->resolution); c.target->addListener(this->dataPtr->thermalMaterialSwitcher.get()); break; } @@ -779,8 +832,7 @@ void Ogre2ThermalCamera::PostRender() unsigned int width = this->ImageWidth(); unsigned int height = this->ImageHeight(); - - PixelFormat format = PF_L16; + PixelFormat format = this->ImageFormat(); Ogre::PixelFormat imageFormat = Ogre2Conversions::Convert(format); int len = width * height; @@ -789,7 +841,8 @@ void Ogre2ThermalCamera::PostRender() if (!this->dataPtr->thermalBuffer) { - this->dataPtr->thermalBuffer = new uint16_t[len * channelCount]; + this->dataPtr->thermalBuffer = + new unsigned char[len * channelCount * bytesPerChannel]; } Ogre::PixelBox dstBox(width, height, 1, imageFormat, this->dataPtr->thermalBuffer); @@ -803,12 +856,32 @@ void Ogre2ThermalCamera::PostRender() this->dataPtr->thermalImage = new uint16_t[len]; } - // fill thermal data - memcpy(this->dataPtr->thermalImage, this->dataPtr->thermalBuffer, - height*width*channelCount*bytesPerChannel); + if (format == PF_L8) + { + // workaround for populating a 16bit image buffer with 8bit data + // \todo(anyone) add a new ConnectNewThermalFrame function that accepts + // a generic unsigned char array instead of uint16_t so we can do a direct + // memcpy of the data + for (unsigned int i = 0u; i < height; ++i) + { + for (unsigned int j = 0u; j < width; ++j) + { + unsigned int idx = i*width + j; + int v = static_cast(this->dataPtr->thermalBuffer[idx]); + this->dataPtr->thermalImage[idx] = static_cast(v); + } + } + } + else + { + // fill thermal data + memcpy(this->dataPtr->thermalImage, this->dataPtr->thermalBuffer, + height*width*channelCount*bytesPerChannel); + } this->dataPtr->newThermalFrame( - this->dataPtr->thermalImage, width, height, 1, "L16"); + this->dataPtr->thermalImage, width, height, 1, + PixelUtil::Name(format)); // Uncomment to debug thermal output // std::cout << "wxh: " << width << " x " << height << std::endl; diff --git a/ogre2/src/media/materials/programs/heat_signature_fs.glsl b/ogre2/src/media/materials/programs/heat_signature_fs.glsl index d01951e53..57faf8b0f 100644 --- a/ogre2/src/media/materials/programs/heat_signature_fs.glsl +++ b/ogre2/src/media/materials/programs/heat_signature_fs.glsl @@ -35,12 +35,16 @@ out vec4 fragColor; uniform float minTemp = 0.0; uniform float maxTemp = 100.0; +uniform int bitDepth; +uniform float resolution; + // map a temperature from the [0, 655.35] range to the [minTemp, maxTemp] -// range (655.35 is the largest Kelvin value allowed) +// range (655.35 is the largest Kelvin value allowed for 16 bit with +// 10mK resolution) float mapNormalized(float num) { float mappedKelvin = ((maxTemp - minTemp) * num) + minTemp; - return mappedKelvin / 655.35; + return mappedKelvin / (((1 << bitDepth) - 1.0) * resolution); } void main() diff --git a/ogre2/src/media/materials/programs/thermal_camera_fs.glsl b/ogre2/src/media/materials/programs/thermal_camera_fs.glsl index 561ba13cf..8bb1c7821 100644 --- a/ogre2/src/media/materials/programs/thermal_camera_fs.glsl +++ b/ogre2/src/media/materials/programs/thermal_camera_fs.glsl @@ -38,6 +38,7 @@ uniform float resolution; uniform float heatSourceTempRange; uniform float ambient; uniform int rgbToTemp; +uniform int bitDepth; float getDepth(vec2 uv) { @@ -51,6 +52,7 @@ void main() // temperature defaults to ambient float temp = ambient; float heatRange = range; + int bitMaxValue = (1 << bitDepth) - 1; // dNorm value is between [0, 1]. It is used to for varying temperature // value of a fragment. @@ -74,7 +76,9 @@ void main() if (isHeatSource) { // heat is normalized so convert back to work in kelvin - temp = heat * 655.35; + // for 16 bit camera and 0.01 resolution: + // ((1 << bitDepth) - 1)* resolution = 655.35 + temp = heat * bitMaxValue * resolution; // set temperature variation for heat source heatRange = heatSourceTempRange; @@ -115,7 +119,8 @@ void main() // apply resolution factor temp /= resolution; // normalize - temp /= 65535.0; + float denorm = float(bitMaxValue); + temp /= denorm; fragColor = vec4(temp, 0, 0, 1.0); } diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index 4c0e72b94..eef2b0e0a 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -23,10 +23,11 @@ #include "test_config.h" // NOLINT(build/include) -#include "ignition/rendering/ThermalCamera.hh" +#include "ignition/rendering/PixelFormat.hh" #include "ignition/rendering/RenderEngine.hh" #include "ignition/rendering/RenderingIface.hh" #include "ignition/rendering/Scene.hh" +#include "ignition/rendering/ThermalCamera.hh" #define DEPTH_TOL 1e-4 #define DOUBLE_TOL 1e-6 @@ -39,7 +40,7 @@ void OnNewThermalFrame(uint16_t *_scanDest, const uint16_t *_scan, unsigned int _channels, const std::string &_format) { - EXPECT_EQ("L16", _format); + // EXPECT_EQ("L16", _format); EXPECT_EQ(50u, _width); EXPECT_EQ(50u, _height); EXPECT_EQ(1u, _channels); @@ -59,6 +60,9 @@ class ThermalCameraTest: public testing::Test, public: void ThermalCameraBoxes(const std::string &_renderEngine, const bool _useHeatSignature); + // Test 8 bit thermal camera output + public: void ThermalCameraBoxes8Bit(const std::string &_renderEngine); + // Path to test textures public: const std::string TEST_MEDIA_PATH = ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), @@ -256,6 +260,193 @@ void ThermalCameraTest::ThermalCameraBoxes( ignition::rendering::unloadEngine(engine->Name()); } +////////////////////////////////////////////////// +void ThermalCameraTest::ThermalCameraBoxes8Bit( + const std::string &_renderEngine) +{ + int imgWidth = 50; + int imgHeight = 50; + double aspectRatio = imgWidth/imgHeight; + + double unitBoxSize = 1.0; + ignition::math::Vector3d boxPosition(1.8, 0.0, 0.0); + + // Only ogre2 supports 8 bit image format + if (_renderEngine.compare("ogre2") != 0) + { + igndbg << "Engine '" << _renderEngine + << "' doesn't support 8 bit thermal cameras" << std::endl; + return; + } + + // Setup ign-rendering with an empty scene + auto *engine = ignition::rendering::engine(_renderEngine); + if (!engine) + { + igndbg << "Engine '" << _renderEngine + << "' is not supported" << std::endl; + return; + } + + ignition::rendering::ScenePtr scene = engine->CreateScene("scene"); + + // red background + scene->SetBackgroundColor(1.0, 0.0, 0.0); + + // Create an scene with a box in it + scene->SetAmbientLight(1.0, 1.0, 1.0); + ignition::rendering::VisualPtr root = scene->RootVisual(); + + // create box visual + ignition::rendering::VisualPtr box = scene->CreateVisual(); + box->AddGeometry(scene->CreateBox()); + box->SetOrigin(0.0, 0.0, 0.0); + box->SetLocalPosition(boxPosition); + box->SetLocalRotation(0, 0, 0); + box->SetLocalScale(unitBoxSize, unitBoxSize, unitBoxSize); + + // set box temperature + float boxTemp = 310.0; + box->SetUserData("temperature", boxTemp); + + root->AddChild(box); + { + // range is hardcoded in shaders + float boxTempRange = 3.0; + double farDist = 10.0; + double nearDist = 0.15; + double hfov = 1.05; + double minTemp = 253.0; + double maxTemp = 673.0; + // Create thermal camera + auto thermalCamera = scene->CreateThermalCamera("ThermalCamera"); + ASSERT_NE(thermalCamera, nullptr); + + ignition::math::Pose3d testPose(ignition::math::Vector3d(0, 0, 0), + ignition::math::Quaterniond::Identity); + thermalCamera->SetLocalPose(testPose); + + // Configure thermal camera + thermalCamera->SetImageWidth(imgWidth); + EXPECT_EQ(thermalCamera->ImageWidth(), + static_cast(imgWidth)); + thermalCamera->SetImageHeight(imgHeight); + EXPECT_EQ(thermalCamera->ImageHeight(), + static_cast(imgHeight)); + thermalCamera->SetFarClipPlane(farDist); + EXPECT_NEAR(thermalCamera->FarClipPlane(), farDist, DOUBLE_TOL); + thermalCamera->SetNearClipPlane(nearDist); + EXPECT_NEAR(thermalCamera->NearClipPlane(), nearDist, DOUBLE_TOL); + thermalCamera->SetAspectRatio(aspectRatio); + EXPECT_NEAR(thermalCamera->AspectRatio(), aspectRatio, DOUBLE_TOL); + thermalCamera->SetHFOV(hfov); + EXPECT_NEAR(thermalCamera->HFOV().Radian(), hfov, DOUBLE_TOL); + + // set bit depth + thermalCamera->SetImageFormat(ignition::rendering::PF_L8); + EXPECT_EQ(ignition::rendering::PF_L8, thermalCamera->ImageFormat()); + + // set min max temp + thermalCamera->SetMinTemperature(minTemp); + EXPECT_DOUBLE_EQ(minTemp, thermalCamera->MinTemperature()); + thermalCamera->SetMaxTemperature(maxTemp); + EXPECT_DOUBLE_EQ(maxTemp, thermalCamera->MaxTemperature()); + + // thermal-specific params + // set room temperature: 294 ~ 298 Kelvin + float ambientTemp = 296.0f; + float ambientTempRange = 4.0f; + + // 8 bit format so higher number here (lower resolution) + // +- 3 degrees + float linearResolution = 3.0f; + thermalCamera->SetAmbientTemperature(ambientTemp); + EXPECT_FLOAT_EQ(ambientTemp, thermalCamera->AmbientTemperature()); + thermalCamera->SetAmbientTemperatureRange(ambientTempRange); + EXPECT_FLOAT_EQ(ambientTempRange, thermalCamera->AmbientTemperatureRange()); + thermalCamera->SetLinearResolution(linearResolution); + EXPECT_FLOAT_EQ(linearResolution, thermalCamera->LinearResolution()); + thermalCamera->SetHeatSourceTemperatureRange(boxTempRange); + EXPECT_FLOAT_EQ(boxTempRange, thermalCamera->HeatSourceTemperatureRange()); + scene->RootVisual()->AddChild(thermalCamera); + + // Set a callback on the camera sensor to get a thermal camera frame + // todo(anyone) change this to uint8_t when thermal cameras supports a + // ConnectNewThermalFrame event that provides this format + uint16_t *thermalData = new uint16_t[imgHeight * imgWidth]; + ignition::common::ConnectionPtr connection = + thermalCamera->ConnectNewThermalFrame( + std::bind(&::OnNewThermalFrame, thermalData, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, + std::placeholders::_4, std::placeholders::_5)); + EXPECT_NE(nullptr, connection); + + // Update once to create image + thermalCamera->Update(); + + // thermal image indices + int midWidth = static_cast(thermalCamera->ImageWidth() * 0.5); + int midHeight = static_cast(thermalCamera->ImageHeight() * 0.5); + int mid = midHeight * thermalCamera->ImageWidth() + midWidth -1; + int left = midHeight * thermalCamera->ImageWidth(); + int right = (midHeight+1) * thermalCamera->ImageWidth() - 1; + + // verify temperature + // Box should be in the middle of image and return box temp + // Left and right side of the image frame should be ambient temp + EXPECT_NEAR(ambientTemp, thermalData[left] * linearResolution, + ambientTempRange); + EXPECT_NEAR(ambientTemp, thermalData[right] * linearResolution, + ambientTempRange); + EXPECT_FLOAT_EQ(thermalData[right], thermalData[left]); + EXPECT_NEAR(boxTemp, thermalData[mid] * linearResolution, boxTempRange); + + std::cerr << " mid " << thermalData[mid] << std::endl; + + // move box in front of near clip plane and verify the thermal + // image returns all box temperature values + ignition::math::Vector3d boxPositionNear( + unitBoxSize * 0.5 + nearDist * 0.5, 0.0, 0.0); + box->SetLocalPosition(boxPositionNear); + thermalCamera->Update(); + + for (unsigned int i = 0; i < thermalCamera->ImageHeight(); ++i) + { + unsigned int step = i * thermalCamera->ImageWidth(); + for (unsigned int j = 0; j < thermalCamera->ImageWidth(); ++j) + { + float temp = thermalData[step + j] * linearResolution; + EXPECT_NEAR(boxTemp, temp, boxTempRange); + } + } + + // move box beyond far clip plane and verify the thermal + // image returns all ambient temperature values + ignition::math::Vector3d boxPositionFar( + unitBoxSize * 0.5 + farDist * 1.5, 0.0, 0.0); + box->SetLocalPosition(boxPositionFar); + thermalCamera->Update(); + + for (unsigned int i = 0; i < thermalCamera->ImageHeight(); ++i) + { + unsigned int step = i * thermalCamera->ImageWidth(); + for (unsigned int j = 0; j < thermalCamera->ImageWidth(); ++j) + { + float temp = thermalData[step + j] * linearResolution; + EXPECT_NEAR(ambientTemp, temp, ambientTempRange); + } + } + + // Clean up + connection.reset(); + delete [] thermalData; + } + + engine->DestroyScene(scene); + ignition::rendering::unloadEngine(engine->Name()); +} + + TEST_P(ThermalCameraTest, ThermalCameraBoxesUniformTemp) { ThermalCameraBoxes(GetParam(), false); @@ -266,6 +457,11 @@ TEST_P(ThermalCameraTest, ThermalCameraBoxesHeatSignature) ThermalCameraBoxes(GetParam(), true); } +TEST_P(ThermalCameraTest, ThermalCameraBoxesUniformTemp8Bit) +{ + ThermalCameraBoxes8Bit(GetParam()); +} + INSTANTIATE_TEST_CASE_P(ThermalCamera, ThermalCameraTest, RENDER_ENGINE_VALUES, ignition::rendering::PrintToStringParam()); From aab3c9eb97da830a2291e5ef1b0933ce9433bc92 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 5 Feb 2021 00:49:55 -0800 Subject: [PATCH 2/9] doc Signed-off-by: Ian Chen --- ogre2/src/Ogre2ThermalCamera.cc | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ogre2/src/Ogre2ThermalCamera.cc b/ogre2/src/Ogre2ThermalCamera.cc index a65940051..1ee80be21 100644 --- a/ogre2/src/Ogre2ThermalCamera.cc +++ b/ogre2/src/Ogre2ThermalCamera.cc @@ -79,7 +79,8 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener /// \param[in] _format Inage format public: void SetFormat(PixelFormat _format); - /// \brieft Set linear resolution + /// \brief Set temperature linear resolution + /// \param[in] _resolution Temperature linear resolution public: void SetLinearResolution(double _resolution); /// \brief Callback when a render target is about to be rendered @@ -133,7 +134,7 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener /// \brief thermal camera image format private: PixelFormat format = PF_L16; - /// \brief thermal camera image format + /// \brief thermal camera image bit depth private: int bitDepth = 16u; }; } From aa2fb9a6e1bf2c4e6e2ae7371ec0051da1b58ebe Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 5 Feb 2021 01:35:15 -0800 Subject: [PATCH 3/9] update test and changelog Signed-off-by: Ian Chen --- Changelog.md | 5 +++++ test/integration/thermal_camera.cc | 4 +--- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/Changelog.md b/Changelog.md index dd103fca7..c7379f223 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,6 +2,11 @@ ### Ignition Rendering 4.X +### Ignition Rendering 4.x.x (202x-xx-xx) + +1. Add support for 8 bit thermal camera image format + * [Pull Request #235](https://github.com/ignitionrobotics/ign-rendering/pull/235) + ### Ignition Rendering 4.3.1 (2021-02-03) 1. Fix converting Pbs to Unlit material conversion (#230) diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index eef2b0e0a..bcfd08f9d 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -40,7 +40,7 @@ void OnNewThermalFrame(uint16_t *_scanDest, const uint16_t *_scan, unsigned int _channels, const std::string &_format) { - // EXPECT_EQ("L16", _format); + EXPECT_TRUE(_format == "L16" || _format == "L8"); EXPECT_EQ(50u, _width); EXPECT_EQ(50u, _height); EXPECT_EQ(1u, _channels); @@ -401,8 +401,6 @@ void ThermalCameraTest::ThermalCameraBoxes8Bit( EXPECT_FLOAT_EQ(thermalData[right], thermalData[left]); EXPECT_NEAR(boxTemp, thermalData[mid] * linearResolution, boxTempRange); - std::cerr << " mid " << thermalData[mid] << std::endl; - // move box in front of near clip plane and verify the thermal // image returns all box temperature values ignition::math::Vector3d boxPositionNear( From 43c80a9b2bd83863d752adb6778e27c673299494 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 8 Feb 2021 14:19:26 -0800 Subject: [PATCH 4/9] style, feedback changes Signed-off-by: Ian Chen --- ogre2/src/Ogre2ThermalCamera.cc | 20 ++++++++++--------- .../materials/programs/heat_signature_fs.glsl | 5 ++--- .../materials/programs/thermal_camera_fs.glsl | 2 +- test/integration/thermal_camera.cc | 4 ++-- 4 files changed, 16 insertions(+), 15 deletions(-) diff --git a/ogre2/src/Ogre2ThermalCamera.cc b/ogre2/src/Ogre2ThermalCamera.cc index 1ee80be21..46ffa5339 100644 --- a/ogre2/src/Ogre2ThermalCamera.cc +++ b/ogre2/src/Ogre2ThermalCamera.cc @@ -76,7 +76,7 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener public: ~Ogre2ThermalCameraMaterialSwitcher() = default; /// \brief Set image format - /// \param[in] _format Inage format + /// \param[in] _format Image format public: void SetFormat(PixelFormat _format); /// \brief Set temperature linear resolution @@ -135,7 +135,7 @@ class Ogre2ThermalCameraMaterialSwitcher : public Ogre::RenderTargetListener private: PixelFormat format = PF_L16; /// \brief thermal camera image bit depth - private: int bitDepth = 16u; + private: unsigned int bitDepth = 16u; }; } } @@ -295,6 +295,7 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( for (unsigned int i = 0; i < item->getNumSubItems(); ++i) { Ogre::SubItem *subItem = item->getSubItem(i); + // normalize temperature value float color = (temp / this->resolution) / ((1 << bitDepth) - 1.0); @@ -346,8 +347,8 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( auto maxTemperature = std::get_if(&maxTempVariant); if (minTemperature && maxTemperature) { - // make sure the temperature range is between [0, 655.35] kelvin - // for 16 bit format and 10mK resolution + // make sure the temperature range is between [min, max] kelvin + // for the given pixel format and camera resolution float maxTemp = ((1 << bitDepth) - 1.0) * this->resolution; Ogre::GpuProgramParametersSharedPtr params = heatSignatureMaterial->getTechnique(0)->getPass(0)-> @@ -356,7 +357,8 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( std::max(static_cast(*minTemperature), 0.0f)); params->setNamedConstant("maxTemp", std::min(static_cast(*maxTemperature), maxTemp)); - params->setNamedConstant("bitDepth", this->bitDepth); + params->setNamedConstant("bitDepth", + static_cast(this->bitDepth)); params->setNamedConstant("resolution", static_cast(this->resolution)); } @@ -867,9 +869,9 @@ void Ogre2ThermalCamera::PostRender() { for (unsigned int j = 0u; j < width; ++j) { - unsigned int idx = i*width + j; - int v = static_cast(this->dataPtr->thermalBuffer[idx]); - this->dataPtr->thermalImage[idx] = static_cast(v); + unsigned int idx = (i * width) + j; + this->dataPtr->thermalImage[idx] = static_cast( + this->dataPtr->thermalBuffer[idx]); } } } @@ -877,7 +879,7 @@ void Ogre2ThermalCamera::PostRender() { // fill thermal data memcpy(this->dataPtr->thermalImage, this->dataPtr->thermalBuffer, - height*width*channelCount*bytesPerChannel); + height * width * channelCount * bytesPerChannel); } this->dataPtr->newThermalFrame( diff --git a/ogre2/src/media/materials/programs/heat_signature_fs.glsl b/ogre2/src/media/materials/programs/heat_signature_fs.glsl index 57faf8b0f..c9a5a5fa0 100644 --- a/ogre2/src/media/materials/programs/heat_signature_fs.glsl +++ b/ogre2/src/media/materials/programs/heat_signature_fs.glsl @@ -38,9 +38,8 @@ uniform float maxTemp = 100.0; uniform int bitDepth; uniform float resolution; -// map a temperature from the [0, 655.35] range to the [minTemp, maxTemp] -// range (655.35 is the largest Kelvin value allowed for 16 bit with -// 10mK resolution) +// map a temperature from the [min, max] range to the user defined +// [minTemp, maxTemp] range float mapNormalized(float num) { float mappedKelvin = ((maxTemp - minTemp) * num) + minTemp; diff --git a/ogre2/src/media/materials/programs/thermal_camera_fs.glsl b/ogre2/src/media/materials/programs/thermal_camera_fs.glsl index 8bb1c7821..f5134f28c 100644 --- a/ogre2/src/media/materials/programs/thermal_camera_fs.glsl +++ b/ogre2/src/media/materials/programs/thermal_camera_fs.glsl @@ -77,7 +77,7 @@ void main() { // heat is normalized so convert back to work in kelvin // for 16 bit camera and 0.01 resolution: - // ((1 << bitDepth) - 1)* resolution = 655.35 + // ((1 << bitDepth) - 1) * resolution = 655.35 temp = heat * bitMaxValue * resolution; // set temperature variation for heat source diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index bcfd08f9d..43fcb6922 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -266,7 +266,7 @@ void ThermalCameraTest::ThermalCameraBoxes8Bit( { int imgWidth = 50; int imgHeight = 50; - double aspectRatio = imgWidth/imgHeight; + double aspectRatio = imgWidth / imgHeight; double unitBoxSize = 1.0; ignition::math::Vector3d boxPosition(1.8, 0.0, 0.0); @@ -312,7 +312,7 @@ void ThermalCameraTest::ThermalCameraBoxes8Bit( root->AddChild(box); { // range is hardcoded in shaders - float boxTempRange = 3.0; + float boxTempRange = 3.0f; double farDist = 10.0; double nearDist = 0.15; double hfov = 1.05; From 8a5bf29ea77db8d83618bc6bb93a5c8f7f29c16c Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 8 Feb 2021 18:00:44 -0800 Subject: [PATCH 5/9] add more doc Signed-off-by: Ian Chen --- test/integration/thermal_camera.cc | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index 43fcb6922..f3e52dcda 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -316,6 +316,10 @@ void ThermalCameraTest::ThermalCameraBoxes8Bit( double farDist = 10.0; double nearDist = 0.15; double hfov = 1.05; + // set min max values based on thermal camera spec + // using the Vividia HTi HT-301 camera as example: + // https://hti-instrument.com/products/ht-301-mobile-phone-thermal-imager + // The range is ~= -20 to 400 degree Celsius double minTemp = 253.0; double maxTemp = 673.0; // Create thermal camera From 3357ac57a4a7628e42c92a03e8e632dc03e445c7 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 9 Feb 2021 20:38:08 -0800 Subject: [PATCH 6/9] disable particles in thermal camera view Signed-off-by: Ian Chen --- .../rendering/ogre2/Ogre2ParticleEmitter.hh | 6 + ogre2/src/Ogre2ParticleEmitter.cc | 4 + ogre2/src/Ogre2ThermalCamera.cc | 8 +- test/integration/thermal_camera.cc | 181 ++++++++++++++++++ 4 files changed, 198 insertions(+), 1 deletion(-) diff --git a/ogre2/include/ignition/rendering/ogre2/Ogre2ParticleEmitter.hh b/ogre2/include/ignition/rendering/ogre2/Ogre2ParticleEmitter.hh index dc9eb7ba5..829dc703b 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2ParticleEmitter.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2ParticleEmitter.hh @@ -86,9 +86,15 @@ namespace ignition public: virtual void SetColorRangeImage(const std::string &_image) override; + /// \brief Particle system visibility flags + public: static uint32_t kParticleVisibilityFlags; + // Documentation inherited. protected: virtual void Init() override; + /// \brief Create the particle system + private: void CreateParticleSystem(); + /// \brief Only the ogre scene can instanstiate this class private: friend class Ogre2Scene; diff --git a/ogre2/src/Ogre2ParticleEmitter.cc b/ogre2/src/Ogre2ParticleEmitter.cc index 7e0e36f08..73ad522b0 100644 --- a/ogre2/src/Ogre2ParticleEmitter.cc +++ b/ogre2/src/Ogre2ParticleEmitter.cc @@ -36,6 +36,8 @@ using namespace ignition; using namespace rendering; +uint32_t Ogre2ParticleEmitter::kParticleVisibilityFlags = 0x00100000; + class ignition::rendering::Ogre2ParticleEmitterPrivate { /// \brief Internal material name. @@ -420,6 +422,8 @@ void Ogre2ParticleEmitter::Init() this->dataPtr->ps->setParticleQuota(500); this->dataPtr->ps->setSortingEnabled(true); + this->dataPtr->ps->setVisibilityFlags(kParticleVisibilityFlags); + IGN_ASSERT(kOgreEmitterTypes.size() == EmitterType::EM_NUM_EMITTERS, "The nummer of supported emitters does not match the number of " "Ogre emitter types."); diff --git a/ogre2/src/Ogre2ThermalCamera.cc b/ogre2/src/Ogre2ThermalCamera.cc index 46ffa5339..5a0cc9ae5 100644 --- a/ogre2/src/Ogre2ThermalCamera.cc +++ b/ogre2/src/Ogre2ThermalCamera.cc @@ -48,6 +48,7 @@ #include "ignition/rendering/ogre2/Ogre2Conversions.hh" #include "ignition/rendering/ogre2/Ogre2Includes.hh" #include "ignition/rendering/ogre2/Ogre2Material.hh" +#include "ignition/rendering/ogre2/Ogre2ParticleEmitter.hh" #include "ignition/rendering/ogre2/Ogre2RenderEngine.hh" #include "ignition/rendering/ogre2/Ogre2RenderTarget.hh" #include "ignition/rendering/ogre2/Ogre2RenderTypes.hh" @@ -737,7 +738,12 @@ void Ogre2ThermalCamera::CreateThermalTexture() colorTargetDef->addPass(Ogre::PASS_CLEAR)); passClear->mColourValue = Ogre::ColourValue(0, 0, 0); // scene pass - colorTargetDef->addPass(Ogre::PASS_SCENE); + Ogre::CompositorPassSceneDef *passScene = + static_cast( + colorTargetDef->addPass(Ogre::PASS_SCENE)); + // thermal camera should not see particles + passScene->mVisibilityMask = IGN_VISIBILITY_ALL & + ~Ogre2ParticleEmitter::kParticleVisibilityFlags; } // rt_input target - converts to thermal diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index f3e52dcda..4dfdcd0ed 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -21,8 +21,11 @@ #include #include +#include + #include "test_config.h" // NOLINT(build/include) +#include "ignition/rendering/ParticleEmitter.hh" #include "ignition/rendering/PixelFormat.hh" #include "ignition/rendering/RenderEngine.hh" #include "ignition/rendering/RenderingIface.hh" @@ -63,6 +66,9 @@ class ThermalCameraTest: public testing::Test, // Test 8 bit thermal camera output public: void ThermalCameraBoxes8Bit(const std::string &_renderEngine); + // Test that particles do not appear in thermal camera image + public: void ThermalCameraParticles(const std::string &_renderEngine); + // Path to test textures public: const std::string TEST_MEDIA_PATH = ignition::common::joinPaths(std::string(PROJECT_SOURCE_PATH), @@ -448,6 +454,176 @@ void ThermalCameraTest::ThermalCameraBoxes8Bit( ignition::rendering::unloadEngine(engine->Name()); } +////////////////////////////////////////////////// +void ThermalCameraTest::ThermalCameraParticles( + const std::string &_renderEngine) +{ + int imgWidth = 50; + int imgHeight = 50; + double aspectRatio = imgWidth / imgHeight; + + double unitBoxSize = 1.0; + ignition::math::Vector3d boxPosition(1.8, 0.0, 0.0); + + // Only ogre2 supports 8 bit image format + if (_renderEngine.compare("ogre2") != 0) + { + igndbg << "Engine '" << _renderEngine + << "' doesn't support 8 bit thermal cameras" << std::endl; + return; + } + + // Setup ign-rendering with an empty scene + auto *engine = ignition::rendering::engine(_renderEngine); + if (!engine) + { + igndbg << "Engine '" << _renderEngine + << "' is not supported" << std::endl; + return; + } + + ignition::rendering::ScenePtr scene = engine->CreateScene("scene"); + + // red background + scene->SetBackgroundColor(1.0, 0.0, 0.0); + + // Create an scene with a box in it + scene->SetAmbientLight(1.0, 1.0, 1.0); + ignition::rendering::VisualPtr root = scene->RootVisual(); + + // create box visual + ignition::rendering::VisualPtr box = scene->CreateVisual(); + box->AddGeometry(scene->CreateBox()); + box->SetOrigin(0.0, 0.0, 0.0); + box->SetLocalPosition(boxPosition); + box->SetLocalRotation(0, 0, 0); + box->SetLocalScale(unitBoxSize, unitBoxSize, unitBoxSize); + + // set box temperature + float boxTemp = 310.0; + box->SetUserData("temperature", boxTemp); + + root->AddChild(box); + + // create particle emitter between camera and box + ignition::rendering::ParticleEmitterPtr emitter = + scene->CreateParticleEmitter(); + emitter->SetLocalPosition(boxPosition - 0.5); + emitter->SetRate(10); + emitter->SetParticleSize({1, 1, 1}); + emitter->SetLifetime(20); + emitter->SetVelocityRange(10, 20); + emitter->SetColorRange(ignition::math::Color::Red, + ignition::math::Color::Black); + emitter->SetScaleRate(10); + emitter->SetEmitting(true); + + root->AddChild(emitter); + + { + double farDist = 10.0; + double nearDist = 0.15; + double hfov = 1.05; + // set min max values based on thermal camera spec + // using the Vividia HTi HT-301 camera as example: + // https://hti-instrument.com/products/ht-301-mobile-phone-thermal-imager + // The range is ~= -20 to 400 degree Celsius + double minTemp = 253.0; + double maxTemp = 673.0; + // Create thermal camera + auto thermalCamera = scene->CreateThermalCamera("ThermalCamera"); + ASSERT_NE(thermalCamera, nullptr); + + ignition::math::Pose3d testPose(ignition::math::Vector3d(0, 0, 0), + ignition::math::Quaterniond::Identity); + thermalCamera->SetLocalPose(testPose); + + // Configure thermal camera + thermalCamera->SetImageWidth(imgWidth); + EXPECT_EQ(thermalCamera->ImageWidth(), + static_cast(imgWidth)); + thermalCamera->SetImageHeight(imgHeight); + EXPECT_EQ(thermalCamera->ImageHeight(), + static_cast(imgHeight)); + thermalCamera->SetFarClipPlane(farDist); + EXPECT_NEAR(thermalCamera->FarClipPlane(), farDist, DOUBLE_TOL); + thermalCamera->SetNearClipPlane(nearDist); + EXPECT_NEAR(thermalCamera->NearClipPlane(), nearDist, DOUBLE_TOL); + thermalCamera->SetAspectRatio(aspectRatio); + EXPECT_NEAR(thermalCamera->AspectRatio(), aspectRatio, DOUBLE_TOL); + thermalCamera->SetHFOV(hfov); + EXPECT_NEAR(thermalCamera->HFOV().Radian(), hfov, DOUBLE_TOL); + + // set bit depth + thermalCamera->SetImageFormat(ignition::rendering::PF_L8); + EXPECT_EQ(ignition::rendering::PF_L8, thermalCamera->ImageFormat()); + + // set min max temp + thermalCamera->SetMinTemperature(minTemp); + EXPECT_DOUBLE_EQ(minTemp, thermalCamera->MinTemperature()); + thermalCamera->SetMaxTemperature(maxTemp); + EXPECT_DOUBLE_EQ(maxTemp, thermalCamera->MaxTemperature()); + + // thermal-specific params + // set room temperature: 294 ~ 298 Kelvin + float ambientTemp = 296.0f; + float ambientTempRange = 4.0f; + + // 8 bit format so higher number here (lower resolution) + // +- 3 degrees + float linearResolution = 3.0f; + thermalCamera->SetAmbientTemperature(ambientTemp); + EXPECT_FLOAT_EQ(ambientTemp, thermalCamera->AmbientTemperature()); + thermalCamera->SetAmbientTemperatureRange(ambientTempRange); + EXPECT_FLOAT_EQ(ambientTempRange, thermalCamera->AmbientTemperatureRange()); + thermalCamera->SetLinearResolution(linearResolution); + EXPECT_FLOAT_EQ(linearResolution, thermalCamera->LinearResolution()); + scene->RootVisual()->AddChild(thermalCamera); + + // Set a callback on the camera sensor to get a thermal camera frame + // todo(anyone) change this to uint8_t when thermal cameras supports a + // ConnectNewThermalFrame event that provides this format + uint16_t *thermalData = new uint16_t[imgHeight * imgWidth]; + ignition::common::ConnectionPtr connection = + thermalCamera->ConnectNewThermalFrame( + std::bind(&::OnNewThermalFrame, thermalData, + std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, + std::placeholders::_4, std::placeholders::_5)); + EXPECT_NE(nullptr, connection); + + // thermal image indices + int midWidth = static_cast(thermalCamera->ImageWidth() * 0.5); + int midHeight = static_cast(thermalCamera->ImageHeight() * 0.5); + int mid = midHeight * thermalCamera->ImageWidth() + midWidth -1; + int left = midHeight * thermalCamera->ImageWidth(); + int right = (midHeight+1) * thermalCamera->ImageWidth() - 1; + + // Update a few times to make sure the flow of particles do not affect + // the readings + for (unsigned int i = 0; i < 100u; ++i) + { + thermalCamera->Update(); + + // verify temperature + // Box should be in the middle of image and return box temp + // Left and right side of the image frame should be ambient temp + EXPECT_NEAR(ambientTemp, thermalData[left] * linearResolution, + ambientTempRange); + EXPECT_NEAR(ambientTemp, thermalData[right] * linearResolution, + ambientTempRange); + EXPECT_FLOAT_EQ(thermalData[right], thermalData[left]); + EXPECT_NEAR(boxTemp, thermalData[mid] * linearResolution, + linearResolution); + } + + // Clean up + connection.reset(); + delete [] thermalData; + } + + engine->DestroyScene(scene); + ignition::rendering::unloadEngine(engine->Name()); +} TEST_P(ThermalCameraTest, ThermalCameraBoxesUniformTemp) { @@ -464,6 +640,11 @@ TEST_P(ThermalCameraTest, ThermalCameraBoxesUniformTemp8Bit) ThermalCameraBoxes8Bit(GetParam()); } +TEST_P(ThermalCameraTest, ThermalCameraParticles) +{ + ThermalCameraParticles(GetParam()); +} + INSTANTIATE_TEST_CASE_P(ThermalCamera, ThermalCameraTest, RENDER_ENGINE_VALUES, ignition::rendering::PrintToStringParam()); From d31a73d0677bf03a53de5e5f4183a899a85a15d3 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 11 Feb 2021 23:19:52 -0800 Subject: [PATCH 7/9] feedback changes Signed-off-by: Ian Chen --- .../ignition/rendering/ogre2/Ogre2ParticleEmitter.hh | 5 +---- ogre2/src/Ogre2ParticleEmitter.cc | 2 +- ogre2/src/Ogre2ThermalCamera.cc | 2 +- test/integration/thermal_camera.cc | 10 +++++----- 4 files changed, 8 insertions(+), 11 deletions(-) diff --git a/ogre2/include/ignition/rendering/ogre2/Ogre2ParticleEmitter.hh b/ogre2/include/ignition/rendering/ogre2/Ogre2ParticleEmitter.hh index 829dc703b..bcc6dd430 100644 --- a/ogre2/include/ignition/rendering/ogre2/Ogre2ParticleEmitter.hh +++ b/ogre2/include/ignition/rendering/ogre2/Ogre2ParticleEmitter.hh @@ -87,14 +87,11 @@ namespace ignition override; /// \brief Particle system visibility flags - public: static uint32_t kParticleVisibilityFlags; + public: static const uint32_t kParticleVisibilityFlags; // Documentation inherited. protected: virtual void Init() override; - /// \brief Create the particle system - private: void CreateParticleSystem(); - /// \brief Only the ogre scene can instanstiate this class private: friend class Ogre2Scene; diff --git a/ogre2/src/Ogre2ParticleEmitter.cc b/ogre2/src/Ogre2ParticleEmitter.cc index 73ad522b0..6eeac530e 100644 --- a/ogre2/src/Ogre2ParticleEmitter.cc +++ b/ogre2/src/Ogre2ParticleEmitter.cc @@ -36,7 +36,7 @@ using namespace ignition; using namespace rendering; -uint32_t Ogre2ParticleEmitter::kParticleVisibilityFlags = 0x00100000; +const uint32_t Ogre2ParticleEmitter::kParticleVisibilityFlags = 0x00100000; class ignition::rendering::Ogre2ParticleEmitterPrivate { diff --git a/ogre2/src/Ogre2ThermalCamera.cc b/ogre2/src/Ogre2ThermalCamera.cc index 5a0cc9ae5..eaac4647e 100644 --- a/ogre2/src/Ogre2ThermalCamera.cc +++ b/ogre2/src/Ogre2ThermalCamera.cc @@ -740,7 +740,7 @@ void Ogre2ThermalCamera::CreateThermalTexture() // scene pass Ogre::CompositorPassSceneDef *passScene = static_cast( - colorTargetDef->addPass(Ogre::PASS_SCENE)); + colorTargetDef->addPass(Ogre::PASS_SCENE)); // thermal camera should not see particles passScene->mVisibilityMask = IGN_VISIBILITY_ALL & ~Ogre2ParticleEmitter::kParticleVisibilityFlags; diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index 4dfdcd0ed..026954de2 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -469,7 +469,7 @@ void ThermalCameraTest::ThermalCameraParticles( if (_renderEngine.compare("ogre2") != 0) { igndbg << "Engine '" << _renderEngine - << "' doesn't support 8 bit thermal cameras" << std::endl; + << "' doesn't support 8 bit thermal cameras" << std::endl; return; } @@ -546,13 +546,13 @@ void ThermalCameraTest::ThermalCameraParticles( EXPECT_EQ(thermalCamera->ImageHeight(), static_cast(imgHeight)); thermalCamera->SetFarClipPlane(farDist); - EXPECT_NEAR(thermalCamera->FarClipPlane(), farDist, DOUBLE_TOL); + EXPECT_DOUBLE_EQ(thermalCamera->FarClipPlane(), farDist); thermalCamera->SetNearClipPlane(nearDist); - EXPECT_NEAR(thermalCamera->NearClipPlane(), nearDist, DOUBLE_TOL); + EXPECT_DOUBLE_EQ(thermalCamera->NearClipPlane(), nearDist); thermalCamera->SetAspectRatio(aspectRatio); - EXPECT_NEAR(thermalCamera->AspectRatio(), aspectRatio, DOUBLE_TOL); + EXPECT_DOUBLE_EQ(thermalCamera->AspectRatio(), aspectRatio); thermalCamera->SetHFOV(hfov); - EXPECT_NEAR(thermalCamera->HFOV().Radian(), hfov, DOUBLE_TOL); + EXPECT_DOUBLE_EQ(thermalCamera->HFOV().Radian(), hfov); // set bit depth thermalCamera->SetImageFormat(ignition::rendering::PF_L8); From 4ff85d307ebb473fe644a569634b2c7f38e2c172 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Thu, 11 Feb 2021 23:31:20 -0800 Subject: [PATCH 8/9] tweak particle params in test Signed-off-by: Ian Chen --- test/integration/thermal_camera.cc | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index 4dfdcd0ed..3f95f001e 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -508,14 +508,14 @@ void ThermalCameraTest::ThermalCameraParticles( // create particle emitter between camera and box ignition::rendering::ParticleEmitterPtr emitter = scene->CreateParticleEmitter(); - emitter->SetLocalPosition(boxPosition - 0.5); + emitter->SetLocalPosition(0.5); emitter->SetRate(10); emitter->SetParticleSize({1, 1, 1}); - emitter->SetLifetime(20); - emitter->SetVelocityRange(10, 20); + emitter->SetLifetime(2); + emitter->SetVelocityRange(0.1, 0.5); emitter->SetColorRange(ignition::math::Color::Red, ignition::math::Color::Black); - emitter->SetScaleRate(10); + emitter->SetScaleRate(1); emitter->SetEmitting(true); root->AddChild(emitter); From 35af1ab625f6d1dfe03f73a17bf587cbbae11b63 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 12 Feb 2021 00:05:19 -0800 Subject: [PATCH 9/9] fix build Signed-off-by: Ian Chen --- test/integration/thermal_camera.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index e28f224c1..dc7144cf3 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -508,7 +508,7 @@ void ThermalCameraTest::ThermalCameraParticles( // create particle emitter between camera and box ignition::rendering::ParticleEmitterPtr emitter = scene->CreateParticleEmitter(); - emitter->SetLocalPosition(0.5); + emitter->SetLocalPosition({0.5, 0, 0}); emitter->SetRate(10); emitter->SetParticleSize({1, 1, 1}); emitter->SetLifetime(2);