From 6d93957ef879c46f878a6888c459f47108c55e6c Mon Sep 17 00:00:00 2001 From: Rhys Date: Mon, 1 Mar 2021 18:29:34 +0000 Subject: [PATCH 01/12] Fix custom_scene_viewer for macOS (#256) * Examples: fix custom_scene_viewer for macOS 1. Add OpenGL context settings for macOS to the DemoWindow. 2. Move glutInit to main 3. Add command line option to set the ogre engine. Signed-off-by: Rhys Mainwaring * Examples: custom_scene_viewer ensure compliance with code standards 1. Use camel case for variables. Signed-off-by: Rhys Mainwaring --- examples/custom_scene_viewer/DemoWindow.cc | 40 ++++++++++++++----- .../custom_scene_viewer/ManualSceneDemo.cc | 25 +++++++++++- 2 files changed, 53 insertions(+), 12 deletions(-) diff --git a/examples/custom_scene_viewer/DemoWindow.cc b/examples/custom_scene_viewer/DemoWindow.cc index 9cb9c645b..95907ccd3 100644 --- a/examples/custom_scene_viewer/DemoWindow.cc +++ b/examples/custom_scene_viewer/DemoWindow.cc @@ -15,10 +15,11 @@ * */ -#if defined(__APPLE__) +#if __APPLE__ #include + #include #include -#elif !defined(_WIN32) +#else #include #include #include @@ -52,7 +53,11 @@ unsigned int imgh = 0; bool g_initContext = false; -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLContextObj g_context; + CGLContextObj g_glutContext; +#elif _WIN32 +#else GLXContext g_context; Display *g_display; GLXDrawable g_drawable; @@ -159,7 +164,10 @@ void printFPS() ////////////////////////////////////////////////// void displayCB() { -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLSetCurrentContext(g_context); +#elif _WIN32 +#else if (g_display) { glXMakeCurrent(g_display, g_drawable, g_context); @@ -171,7 +179,10 @@ void displayCB() camera->Capture(*g_image); -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLSetCurrentContext(g_glutContext); +#elif _WIN32 +#else glXMakeCurrent(g_glutDisplay, g_glutDrawable, g_glutContext); #endif @@ -198,7 +209,10 @@ void idleCB() ////////////////////////////////////////////////// void keyboardCB(unsigned char _key, int, int) { -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLSetCurrentContext(g_context); +#elif _WIN32 +#else if (g_display) { glXMakeCurrent(g_display, g_drawable, g_context); @@ -241,7 +255,10 @@ void keyboardCB(unsigned char _key, int, int) g_demo->SelectScene(index); } -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLSetCurrentContext(g_glutContext); +#elif _WIN32 +#else glXMakeCurrent(g_glutDisplay, g_glutDrawable, g_glutContext); #endif } @@ -259,9 +276,6 @@ void initCamera(CameraPtr _camera) ////////////////////////////////////////////////// void initContext() { - int argc = 0; - char **argv = 0; - glutInit(&argc, argv); glutInitDisplayMode(GLUT_DOUBLE); glutInitWindowPosition(0, 0); glutInitWindowSize(imgw, imgh); @@ -278,6 +292,9 @@ void initContext() ////////////////////////////////////////////////// void run(ManualSceneDemoPtr _demo) { +#if __APPLE__ + g_context = CGLGetCurrentContext(); +#endif #if not (__APPLE__ || _WIN32) g_context = glXGetCurrentContext(); g_display = glXGetCurrentDisplay(); @@ -290,6 +307,9 @@ void run(ManualSceneDemoPtr _demo) initContext(); printUsage(); +#if __APPLE__ + g_glutContext = CGLGetCurrentContext(); +#endif #if not (__APPLE__ || _WIN32) g_glutDisplay = glXGetCurrentDisplay(); g_glutDrawable = glXGetCurrentDrawable(); diff --git a/examples/custom_scene_viewer/ManualSceneDemo.cc b/examples/custom_scene_viewer/ManualSceneDemo.cc index bf6d4c696..f65744945 100644 --- a/examples/custom_scene_viewer/ManualSceneDemo.cc +++ b/examples/custom_scene_viewer/ManualSceneDemo.cc @@ -14,6 +14,16 @@ * limitations under the License. * */ + +#if defined(__APPLE__) + #include + #include +#elif not defined(_WIN32) + #include + #include + #include +#endif + #include #include #include "ManualSceneDemo.hh" @@ -169,8 +179,18 @@ void ManualSceneDemo::ChangeScene() ////////////////////////////////////////////////// ////////////////////////////////////////////////// -int main(int, char**) +int main(int _argc, char** _argv) { + glutInit(&_argc, _argv); + + // Expose engine name to command line because we can't instantiate both + // ogre and ogre2 at the same time + std::string ogreEngine("ogre"); + if (_argc > 1) + { + ogreEngine = _argv[1]; + } + common::Console::SetVerbosity(4); //! [add scenes] ManualSceneDemoPtr sceneDemo(new ManualSceneDemo); @@ -188,8 +208,9 @@ int main(int, char**) sceneDemo->AddScene(SceneBuilderPtr(new ShadowSceneBuilder(4))); sceneDemo->AddScene(SceneBuilderPtr(new ShadowSceneBuilder(5))); //! [add scenes] - sceneDemo->AddCamera("ogre"); + sceneDemo->AddCamera(ogreEngine); sceneDemo->AddCamera("optix"); sceneDemo->Run(); return 0; } + From fff0dbd1a060ea83102f6e3d9ca1e1a8a836e8fa Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 1 Mar 2021 22:29:08 -0800 Subject: [PATCH 02/12] Improve particle scattering noise (#261) * increase nosie std based on particle emitter size Signed-off-by: Ian Chen * tuning particle noise in shaders Signed-off-by: Ian Chen * apply change to depth camera Signed-off-by: Ian Chen * fix depth camera particle noise Signed-off-by: Ian Chen * fix tests Signed-off-by: Ian Chen * fix point cloud scattering Signed-off-by: Ian Chen Co-authored-by: Nate Koenig --- ogre2/src/Ogre2DepthCamera.cc | 52 ++++++++++- ogre2/src/Ogre2GpuRays.cc | 21 ++++- ogre2/src/Ogre2ParticleEmitter.cc | 3 +- ogre2/src/Ogre2ParticleNoiseListener.cc | 89 +++++++++++++++++++ ogre2/src/Ogre2ParticleNoiseListener.hh | 53 +++++++++++ .../materials/programs/depth_camera_fs.glsl | 34 +++++-- .../programs/gpu_rays_1st_pass_fs.glsl | 23 ++++- test/integration/depth_camera.cc | 7 +- test/integration/gpu_rays.cc | 9 +- 9 files changed, 266 insertions(+), 25 deletions(-) create mode 100644 ogre2/src/Ogre2ParticleNoiseListener.cc create mode 100644 ogre2/src/Ogre2ParticleNoiseListener.hh diff --git a/ogre2/src/Ogre2DepthCamera.cc b/ogre2/src/Ogre2DepthCamera.cc index 5979e07c8..3d24c10a9 100644 --- a/ogre2/src/Ogre2DepthCamera.cc +++ b/ogre2/src/Ogre2DepthCamera.cc @@ -38,6 +38,8 @@ #include "ignition/rendering/ogre2/Ogre2Scene.hh" #include "ignition/rendering/ogre2/Ogre2Sensor.hh" +#include "Ogre2ParticleNoiseListener.hh" + namespace ignition { namespace rendering @@ -134,7 +136,11 @@ class ignition::rendering::Ogre2DepthCameraPrivate /// \brief Particle scatter ratio. This is used to determine the ratio of /// particles that will detected by the depth camera - public: double particleScatterRatio = 0.1; + public: double particleScatterRatio = 0.65; + + /// \brief Listener for setting particle noise value based on particle + /// emitter region + public: std::unique_ptr particleNoiseListener; }; using namespace ignition; @@ -869,6 +875,25 @@ void Ogre2DepthCamera::CreateDepthTexture() this->dataPtr->ogreCompositorWorkspace = ogreCompMgr->addWorkspace(this->scene->OgreSceneManager(), rt, this->ogreCamera, wsDefName, false); + + // add the listener + Ogre::CompositorNode *node = + this->dataPtr->ogreCompositorWorkspace->getNodeSequence()[0]; + auto channelsTex = node->getLocalTextures(); + + for (auto c : channelsTex) + { + if (c.textures[0]->getSrcFormat() == Ogre::PF_L8) + { + // add particle noise / scatter effects listener so we can set the + // amount of noise based on size of emitter + this->dataPtr->particleNoiseListener.reset( + new Ogre2ParticleNoiseListener(this->scene, + this->ogreCamera, this->dataPtr->depthMaterial)); + c.target->addListener(this->dataPtr->particleNoiseListener.get()); + break; + } + } } ////////////////////////////////////////////////// @@ -897,6 +922,31 @@ void Ogre2DepthCamera::PreRender() this->dataPtr->renderPassDirty); for (auto &pass : this->dataPtr->renderPasses) pass->PreRender(); + + + // add the particle noise listener again if worksapce is recreated due to + // dirty render pass + if (this->dataPtr->renderPassDirty) + { + Ogre::CompositorNode *node = + this->dataPtr->ogreCompositorWorkspace->getNodeSequence()[0]; + auto channelsTex = node->getLocalTextures(); + + for (auto c : channelsTex) + { + if (c.textures[0]->getSrcFormat() == Ogre::PF_L8) + { + // add particle noise / scatter effects listener so we can set the + // amount of noise based on size of emitter + this->dataPtr->particleNoiseListener.reset( + new Ogre2ParticleNoiseListener(this->scene, + this->ogreCamera, this->dataPtr->depthMaterial)); + c.target->addListener(this->dataPtr->particleNoiseListener.get()); + break; + } + } + } + this->dataPtr->renderPassDirty = false; } diff --git a/ogre2/src/Ogre2GpuRays.cc b/ogre2/src/Ogre2GpuRays.cc index 0d19589fa..417d4b838 100644 --- a/ogre2/src/Ogre2GpuRays.cc +++ b/ogre2/src/Ogre2GpuRays.cc @@ -34,6 +34,8 @@ #include "ignition/rendering/ogre2/Ogre2Sensor.hh" #include "ignition/rendering/ogre2/Ogre2Visual.hh" +#include "Ogre2ParticleNoiseListener.hh" + namespace ignition { namespace rendering @@ -169,7 +171,11 @@ class ignition::rendering::Ogre2GpuRaysPrivate /// \brief Particle scatter ratio. This is used to determine the ratio of /// particles that will detected by the depth camera - public: double particleScatterRatio = 0.1; + public: double particleScatterRatio = 0.65; + + /// \brief Listener for setting particle noise value based on particle + /// emitter region + public: std::unique_ptr particleNoiseListener[6]; }; using namespace ignition; @@ -878,9 +884,6 @@ void Ogre2GpuRays::Setup1stPass() ogreCompMgr->addWorkspace(this->scene->OgreSceneManager(), rt, this->dataPtr->cubeCam[i], wsDefName, false); - // add laser retro material switcher to render target listener - // so we can switch to use laser retro material when the camera is being - // updated Ogre::CompositorNode *node = this->dataPtr->ogreCompositorWorkspace1st[i]->getNodeSequence()[0]; auto channelsTex = node->getLocalTextures(); @@ -889,10 +892,20 @@ void Ogre2GpuRays::Setup1stPass() { if (c.textures[0]->getSrcFormat() == Ogre::PF_R8G8B8) { + // add laser retro material switcher to render target listener + // so we can switch to use laser retro material when the camera is being + // updated this->dataPtr->laserRetroMaterialSwitcher[i].reset( new Ogre2LaserRetroMaterialSwitcher(this->scene)); c.target->addListener( this->dataPtr->laserRetroMaterialSwitcher[i].get()); + + // add particle noise / scatter effects listener so we can set the + // amount of noise based on size of emitter + this->dataPtr->particleNoiseListener[i].reset( + new Ogre2ParticleNoiseListener(this->scene, + this->dataPtr->cubeCam[i], this->dataPtr->matFirstPass)); + c.target->addListener(this->dataPtr->particleNoiseListener[i].get()); break; } } diff --git a/ogre2/src/Ogre2ParticleEmitter.cc b/ogre2/src/Ogre2ParticleEmitter.cc index 39a430eb7..31ebfdd6a 100644 --- a/ogre2/src/Ogre2ParticleEmitter.cc +++ b/ogre2/src/Ogre2ParticleEmitter.cc @@ -277,6 +277,7 @@ void Ogre2ParticleEmitter::SetMaterial(const MaterialPtr &_material) auto ogreMaterial = std::dynamic_pointer_cast(_material); ogreMaterial->FillUnlitDatablock(this->dataPtr->ogreDatablock); + this->material = _material; } @@ -286,7 +287,6 @@ void Ogre2ParticleEmitter::SetVelocityRange(double _minVelocity, { this->dataPtr->emitter->setParticleVelocity(_minVelocity, _maxVelocity); - this->minVelocity = _minVelocity; this->maxVelocity = _maxVelocity; } @@ -501,6 +501,7 @@ void Ogre2ParticleEmitter::CreateParticleSystem() auto ogreMat = std::dynamic_pointer_cast( this->dataPtr->materialUnlit); this->dataPtr->ogreDatablock = ogreMat->UnlitDatablock(); + this->dataPtr->ps->setMaterialName( *(this->dataPtr->ogreDatablock->getNameStr())); diff --git a/ogre2/src/Ogre2ParticleNoiseListener.cc b/ogre2/src/Ogre2ParticleNoiseListener.cc new file mode 100644 index 000000000..67e29cf37 --- /dev/null +++ b/ogre2/src/Ogre2ParticleNoiseListener.cc @@ -0,0 +1,89 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ + +#include "ignition/rendering/ogre2/Ogre2Includes.hh" +#include "ignition/rendering/ogre2/Ogre2RenderTypes.hh" +#include "ignition/rendering/ogre2/Ogre2Scene.hh" + +#include "Ogre2ParticleNoiseListener.hh" + +using namespace ignition; +using namespace rendering; + +////////////////////////////////////////////////// +Ogre2ParticleNoiseListener::Ogre2ParticleNoiseListener( + Ogre2ScenePtr _scene, Ogre::Camera *_ogreCamera, + Ogre::MaterialPtr _ogreMaterial) +{ + this->scene = _scene; + this->ogreCamera = _ogreCamera; + this->ogreMaterial = _ogreMaterial; +} + +////////////////////////////////////////////////// +void Ogre2ParticleNoiseListener::preRenderTargetUpdate( + const Ogre::RenderTargetEvent & /*_evt*/) +{ + // the code here is responsible for setting the depth variation of readings + // returned by sensor in areas where particles are. It does so by adding + // noise with high std dev values. + // 1. Find first particle in the view of the sensor + // 2. set the sensor noise for the particles to half the size of the + // bounding box + // \todo(anyone) noise std dev is set based on the first particle emitter the + // sensor sees. Make this scale to multiple particle emitters! + auto itor = this->scene->OgreSceneManager()->getMovableObjectIterator( + Ogre::ParticleSystemFactory::FACTORY_TYPE_NAME); + while (itor.hasMoreElements()) + { + Ogre::MovableObject *object = itor.peekNext(); + Ogre::ParticleSystem *ps = dynamic_cast(object); + + if (!ps) + { + itor.moveNext(); + continue; + } + + Ogre::Aabb aabb = ps->getWorldAabbUpdated(); + if (std::isinf(aabb.getMinimum().length()) || + std::isinf(aabb.getMaximum().length())) + { + itor.moveNext(); + continue; + } + + Ogre::AxisAlignedBox box = Ogre::AxisAlignedBox(aabb.getMinimum(), + aabb.getMaximum()); + + + if (this->ogreCamera->isVisible(box)) + { + // set stddev to half of size of particle emitter aabb + auto hs = box.getHalfSize() * 0.5; + double particleStddev = hs.x; + + Ogre::Pass *pass = this->ogreMaterial->getTechnique(0)->getPass(0); + Ogre::GpuProgramParametersSharedPtr psParams = + pass->getFragmentProgramParameters(); + psParams->setNamedConstant("particleStddev", + static_cast(particleStddev)); + return; + } + itor.moveNext(); + } +} diff --git a/ogre2/src/Ogre2ParticleNoiseListener.hh b/ogre2/src/Ogre2ParticleNoiseListener.hh new file mode 100644 index 000000000..1c4db2e54 --- /dev/null +++ b/ogre2/src/Ogre2ParticleNoiseListener.hh @@ -0,0 +1,53 @@ +/* + * Copyright (C) 2020 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + */ +#ifndef IGNITION_RENDERING_OGRE2_OGRE2PARTICLENOISELISTENER_HH_ +#define IGNITION_RENDERING_OGRE2_OGRE2PARTICLENOISELISTENER_HH_ + +namespace ignition +{ + namespace rendering + { + inline namespace IGNITION_RENDERING_VERSION_NAMESPACE { + // + /// \brief Helper class for updating particle noise params + class Ogre2ParticleNoiseListener : public Ogre::RenderTargetListener + { + /// \brief constructor + /// \param[in] _scene the scene manager responsible for rendering + public: Ogre2ParticleNoiseListener(Ogre2ScenePtr _scene, + Ogre::Camera *_ogreCamera, Ogre::MaterialPtr _ogreMaterial); + + /// \brief destructor + public: ~Ogre2ParticleNoiseListener() = default; + + /// \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. + private: virtual void preRenderTargetUpdate( + const Ogre::RenderTargetEvent &_evt) override; + + private: Ogre2ScenePtr scene; + private: Ogre::Camera *ogreCamera = nullptr; + private: Ogre::MaterialPtr ogreMaterial; + }; + } + } +} + +#endif + + diff --git a/ogre2/src/media/materials/programs/depth_camera_fs.glsl b/ogre2/src/media/materials/programs/depth_camera_fs.glsl index 856f7aa1f..dd9a894ca 100644 --- a/ogre2/src/media/materials/programs/depth_camera_fs.glsl +++ b/ogre2/src/media/materials/programs/depth_camera_fs.glsl @@ -88,7 +88,6 @@ void main() float fDepth = texture(depthTexture, inPs.uv0).x; float d = projectionParams.y / (fDepth - projectionParams.x); - // reconstruct 3d viewspace pos from depth vec3 viewSpacePos = inPs.cameraDir * d; @@ -104,7 +103,7 @@ void main() // return particle depth if it can be seen by the camera and not obstructed // by other objects in the camera view - if (particle.x > 0 && particleDepth > 0.0 && particleDepth < fDepth) + if (particle.x > 0 && particleDepth < fDepth) { // apply scatter effect so that only some of the smoke pixels are visible float r = rand(inPs.uv0 + vec2(time, time)); @@ -113,12 +112,29 @@ void main() // set point to 3d pos of particle pixel float pd = projectionParams.y / (particleDepth - projectionParams.x); vec3 particleViewSpacePos = inPs.cameraDir * pd; - point = vec3(-particleViewSpacePos.z, -particleViewSpacePos.x, + vec3 particlePoint = vec3(-particleViewSpacePos.z, -particleViewSpacePos.x, particleViewSpacePos.y); - // apply gaussian noise to particle depth data - point = point + gaussrand(inPs.uv0, vec3(time, time, time), - particleStddev, 0.0).xyz; + float rr = rand(inPs.uv0 + vec2(1.0/time, time)) - 0.5; + + // apply gaussian noise to particle point cloud data + // With large particles, the range returned are all from the first large + // particle. So add noise with some mean values so that all the points are + // shifted further out. This gives depth readings beyond the first few + // particles and avoid too many early returns + vec3 noise = gaussrand(inPs.uv0, vec3(time, time, time), + particleStddev, rr*rr*particleStddev*0.5).xyz; + float noiseLength = length(noise); + float particlePointLength = length(particlePoint); + float newLength = particlePointLength + noiseLength; + vec3 newPoint = particlePoint * (newLength / particlePointLength); + + // make sure we do not produce depth values larger than depth of first + // non-particle obstacle, e.g. a box behind particle should still return + // a hit + float pointLength = length(point); + if (newLength < pointLength) + point = newPoint; } } @@ -153,7 +169,11 @@ void main() point.x = min; } - color = vec4(backgroundColor, 1.0); + // clamp to background color only if it is not a particle pixel + if (particle.x < 1e-6) + { + color = vec4(backgroundColor, 1.0); + } } // gamma correct - using same method as: diff --git a/ogre2/src/media/materials/programs/gpu_rays_1st_pass_fs.glsl b/ogre2/src/media/materials/programs/gpu_rays_1st_pass_fs.glsl index 410e8511f..6911933bc 100644 --- a/ogre2/src/media/materials/programs/gpu_rays_1st_pass_fs.glsl +++ b/ogre2/src/media/materials/programs/gpu_rays_1st_pass_fs.glsl @@ -88,7 +88,8 @@ void main() vec4 particle = texture(particleTexture, inPs.uv0); float particleDepth = texture(particleDepthTexture, inPs.uv0).x; - if (particle.x > 0.0 && particleDepth > 0.0 && particleDepth < fDepth) + // check if need to apply scatter effect + if (particle.x > 0.0 && particleDepth < fDepth) { // apply scatter effect so that only some of the smoke pixels are visible float r = rand(inPs.uv0 + vec2(time, time)); @@ -97,11 +98,25 @@ void main() float pd = projectionParams.y / (particleDepth - projectionParams.x); vec3 point = inPs.cameraDir * pd; + float rr = rand(inPs.uv0 + vec2(1.0/time, time)) - 0.5; + + // apply gaussian noise to particle range data + // With large particles, the range returned are all from the first large + // particle. So add noise with some mean values so that all the points are + // shifted further out. This gives depth readings beyond the first few + // particles and avoid too many early returns + vec3 noise = gaussrand(inPs.uv0, vec3(time, time, time), + particleStddev, rr*rr*particleStddev*0.5).xyz; + float noiseLength = length(noise); + // apply gaussian noise to particle depth data - point = point + gaussrand(inPs.uv0, vec3(time, time, time), - particleStddev, 0.0).xyz; + float newLength = length(point) + noiseLength; - l = length(point); + // make sure we do not produce values larger than the range of the first + // non-particle obstacle, e.g. a box behind particle should still return + // a hit + if (newLength < l) + l = newLength; } } diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index aa79648c5..5794ec885 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -606,7 +606,7 @@ void DepthCameraTest::DepthCameraParticles( emitter->SetRate(100); emitter->SetLifetime(2); emitter->SetVelocityRange(0.1, 0.1); - emitter->SetScaleRate(0.2); + emitter->SetScaleRate(0.1); emitter->SetColorRange(ignition::math::Color::Red, ignition::math::Color::Black); emitter->SetEmitting(true); @@ -628,9 +628,8 @@ void DepthCameraTest::DepthCameraParticles( double depthParticleAvg = 0.0; // set a larger tol for particle depth - // tol is particle size + 4 sigma of noise stddev - double noiseStddev = 0.01; - double depthNoiseTol = particleSize.X() + 4 * noiseStddev;; + // depth noise is computed based on particle size + double depthNoiseTol = particleSize.X() + particleSize.X() * 0.5; double expectedParticleDepth = particlePosition.X(); // Verify depth and point cloud data after particle effects diff --git a/test/integration/gpu_rays.cc b/test/integration/gpu_rays.cc index 81bf2cedc..a8b751dc2 100644 --- a/test/integration/gpu_rays.cc +++ b/test/integration/gpu_rays.cc @@ -558,7 +558,7 @@ void GpuRaysTest::RaysParticles(const std::string &_renderEngine) emitter->SetRate(100); emitter->SetLifetime(2); emitter->SetVelocityRange(0.1, 0.1); - emitter->SetScaleRate(0.2); + emitter->SetScaleRate(0.1); emitter->SetColorRange(ignition::math::Color::Red, ignition::math::Color::Black); emitter->SetEmitting(true); @@ -584,7 +584,8 @@ void GpuRaysTest::RaysParticles(const std::string &_renderEngine) abs(box02Pose.Pos().Y()) - unitBoxSize / 2; // set a larger tol for particle range - double laserNoiseTol = particleSize.X(); + // depth noise is computed based on particle size + double laserNoiseTol = particleSize.X() + particleSize.X() * 0.5; double expectedParticleRange = particlePosition.X(); // update 100 frames. There should be a descent chance that we will see both @@ -615,10 +616,10 @@ void GpuRaysTest::RaysParticles(const std::string &_renderEngine) EXPECT_DOUBLE_EQ(ignition::math::INF_D, scan[last]); } - // particles are sparse so there should be more misses than hits - EXPECT_GT(particleMissCount, particleHitCount); // there should be at least one hit EXPECT_GT(particleHitCount, 0u); + // there should be at least one miss + EXPECT_GT(particleMissCount, 0u); c.reset(); From bc5dfa4ab646e4a22bd8d7ae3d5fc8ac8050dc37 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Mon, 1 Mar 2021 23:22:38 -0800 Subject: [PATCH 03/12] 4.6.0 (#262) * changelog Signed-off-by: Ian Chen * update cmake version Signed-off-by: Ian Chen --- CMakeLists.txt | 2 +- Changelog.md | 8 ++++++++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5122d8ff9..028b47109 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-rendering4 VERSION 4.5.0) +project(ignition-rendering4 VERSION 4.6.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 2d0803189..73375111a 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,6 +2,14 @@ ### Ignition Rendering 4.X +### Ignition Rendering 4.6.0 (2021-03-01) + +1. Improve particle scattering noise + * [Pull Request #261](https://github.com/ignitionrobotics/ign-rendering/pull/261) + +1. Fix custom_scene_viewer for macOS + * [Pull Request #256](https://github.com/ignitionrobotics/ign-rendering/pull/256) + ### Ignition Rendering 4.5.0 (2021-02-17) 1. More verbose messages when failing to load render engines From 7712a7c735ae3c2cfb16b1bf5f1bd14934521bca Mon Sep 17 00:00:00 2001 From: Rein Appeldoorn Date: Tue, 2 Mar 2021 19:17:21 +0100 Subject: [PATCH 04/12] fix(typo): sencod --> second (#263) Signed-off-by: Rein Appeldoorn --- ogre/src/OgreGpuRays.cc | 2 +- ogre2/src/Ogre2GpuRays.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ogre/src/OgreGpuRays.cc b/ogre/src/OgreGpuRays.cc index 2dba203b6..aa081fda8 100644 --- a/ogre/src/OgreGpuRays.cc +++ b/ogre/src/OgreGpuRays.cc @@ -50,7 +50,7 @@ class ignition::rendering::OgreGpuRaysPrivate /// \brief Pointer to Ogre material for the first rendering pass. public: Ogre::Material *matFirstPass = nullptr; - /// \brief Pointer to Ogre material for the sencod rendering pass. + /// \brief Pointer to Ogre material for the second rendering pass. public: Ogre::Material *matSecondPass = nullptr; /// \brief Temporary pointer to the current material. diff --git a/ogre2/src/Ogre2GpuRays.cc b/ogre2/src/Ogre2GpuRays.cc index 417d4b838..effc70192 100644 --- a/ogre2/src/Ogre2GpuRays.cc +++ b/ogre2/src/Ogre2GpuRays.cc @@ -107,7 +107,7 @@ class ignition::rendering::Ogre2GpuRaysPrivate /// \brief Pointer to Ogre material for the first rendering pass. public: Ogre::MaterialPtr matFirstPass; - /// \brief Pointer to Ogre material for the sencod rendering pass. + /// \brief Pointer to Ogre material for the second rendering pass. public: Ogre::MaterialPtr matSecondPass; /// \brief Cubemap cameras From 8af7fbc0869762dfadf267af7bbbdff6f5590b34 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 2 Mar 2021 16:35:46 -0800 Subject: [PATCH 05/12] enable depth write in particles example (#217) Signed-off-by: Ian Chen Co-authored-by: Ashton Larkin <42042756+adlarkin@users.noreply.github.com> --- examples/particles_demo/Main.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/particles_demo/Main.cc b/examples/particles_demo/Main.cc index 69de0e15d..3386cbb32 100644 --- a/examples/particles_demo/Main.cc +++ b/examples/particles_demo/Main.cc @@ -103,7 +103,6 @@ void buildScene(ScenePtr _scene) particleMaterial->SetDiffuse(0.7, 0.7, 0.7); particleMaterial->SetTexture(RESOURCE_PATH + "/smoke.png"); particleMaterial->SetAlphaFromTexture(true); - particleMaterial->SetDepthWriteEnabled(false); //! [create particle emitter] ParticleEmitterPtr emitter = _scene->CreateParticleEmitter(); From 886d0d93bdd579a7e99fae474386be034d96c64e Mon Sep 17 00:00:00 2001 From: Rhys Date: Mon, 8 Mar 2021 23:44:24 +0000 Subject: [PATCH 06/12] Fix gazebo_scene_viewer for macOS and ensure exits cleanly (#259) * Examples: fix gazebo_scene_viewer for macOS and ensure exits cleanly 1. Add OpenGL context settings for macOS to the CameraWindow. 2. Move glutInit to main in GazeboDemo and GazeboWorldDemo 3. Update CMakeLists.txt to exclude libstdc++fs for macOS and add find_package for bullet. 4. Expose command line option to set either ogre or ogre2 as an engine. 5. Ensure gazebo::transport is stopped and cleaned up prior to exit. 6. Use std::unique_ptr to manage current and new scene manager lifetimes. 7. Disconnect pub/sub from transport on SceneManager Fini. 8. Add checks in pub/sub callbacks to ensure scene manager pointers are valid. Signed-off-by: Rhys Mainwaring * Examples: gazebo_scene_viewer ensure compliance with code standards 1. Place return in braces following if 2. Use camel case for variables. Signed-off-by: Rhys Mainwaring * Examples: revert addition of Bullet to CMakeLists.txt in gazebo_scene_viewer Signed-off-by: Rhys Mainwaring --- examples/gazebo_scene_viewer/CMakeLists.txt | 5 +- examples/gazebo_scene_viewer/CameraWindow.cc | 44 ++++++++++++++---- examples/gazebo_scene_viewer/GazeboDemo.cc | 24 +++++++++- .../gazebo_scene_viewer/GazeboWorldDemo.cc | 24 +++++++++- examples/gazebo_scene_viewer/SceneManager.cc | 46 +++++++++++++++++-- .../SceneManagerPrivate.hh | 5 +- 6 files changed, 127 insertions(+), 21 deletions(-) diff --git a/examples/gazebo_scene_viewer/CMakeLists.txt b/examples/gazebo_scene_viewer/CMakeLists.txt index 9ff4b937a..1dbbded56 100644 --- a/examples/gazebo_scene_viewer/CMakeLists.txt +++ b/examples/gazebo_scene_viewer/CMakeLists.txt @@ -17,6 +17,7 @@ if (NOT APPLE) find_package(GLEW REQUIRED) include_directories(SYSTEM ${GLEW_INCLUDE_DIRS}) link_directories(${GLEW_LIBRARY_DIRS}) + set(STD_CXX_FS_LIBRARIES "stdc++fs") endif() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-deprecated-declarations") @@ -33,7 +34,7 @@ target_link_libraries(gazebo_scene_viewer ${GLEW_LIBRARIES} ${GAZEBO_LIBRARIES} ${IGNITION-RENDERING_LIBRARIES} - stdc++fs + ${STD_CXX_FS_LIBRARIES} ) add_executable(gazebo_scene_viewer2_demo @@ -48,5 +49,5 @@ target_link_libraries(gazebo_scene_viewer2_demo ${GLEW_LIBRARIES} ${GAZEBO_LIBRARIES} ${IGNITION-RENDERING_LIBRARIES} - stdc++fs + ${STD_CXX_FS_LIBRARIES} ) diff --git a/examples/gazebo_scene_viewer/CameraWindow.cc b/examples/gazebo_scene_viewer/CameraWindow.cc index 0a662990b..2164a753b 100644 --- a/examples/gazebo_scene_viewer/CameraWindow.cc +++ b/examples/gazebo_scene_viewer/CameraWindow.cc @@ -18,6 +18,7 @@ #if __APPLE__ #include + #include #include #else #include @@ -30,6 +31,7 @@ #endif #include +#include #include #include @@ -52,7 +54,11 @@ gz::ImagePtr g_image; bool g_initContext = false; -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLContextObj g_context; + CGLContextObj g_glutContext; +#elif _WIN32 +#else GLXContext g_context; Display *g_display; GLXDrawable g_drawable; @@ -66,7 +72,10 @@ double g_offset = 0.0; ////////////////////////////////////////////////// void GlutRun(std::vector _cameras) { -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + g_context = CGLGetCurrentContext(); +#elif _WIN32 +#else g_context = glXGetCurrentContext(); g_display = glXGetCurrentDisplay(); g_drawable = glXGetCurrentDrawable(); @@ -77,7 +86,10 @@ void GlutRun(std::vector _cameras) GlutInitContext(); GlutPrintUsage(); -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + g_glutContext = CGLGetCurrentContext(); +#elif _WIN32 +#else g_glutDisplay = glXGetCurrentDisplay(); g_glutDrawable = glXGetCurrentDrawable(); g_glutContext = glXGetCurrentContext(); @@ -89,7 +101,10 @@ void GlutRun(std::vector _cameras) ////////////////////////////////////////////////// void GlutDisplay() { -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLSetCurrentContext(g_context); +#elif _WIN32 +#else if (g_display) { glXMakeCurrent(g_display, g_drawable, g_context); @@ -98,7 +113,10 @@ void GlutDisplay() g_cameras[g_cameraIndex]->Capture(*g_image); -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLSetCurrentContext(g_glutContext); +#elif _WIN32 +#else glXMakeCurrent(g_glutDisplay, g_glutDrawable, g_glutContext); #endif @@ -116,7 +134,10 @@ void GlutDisplay() ////////////////////////////////////////////////// void GlutIdle() { -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLSetCurrentContext(g_context); +#elif _WIN32 +#else if (g_display) { glXMakeCurrent(g_display, g_drawable, g_context); @@ -128,7 +149,10 @@ void GlutIdle() manager->UpdateScenes(); -#if not (__APPLE__ || _WIN32) +#if __APPLE__ + CGLSetCurrentContext(g_glutContext); +#elif _WIN32 +#else glXMakeCurrent(g_glutDisplay, g_glutDrawable, g_glutContext); #endif @@ -140,6 +164,9 @@ void GlutKeyboard(unsigned char _key, int, int) { if (_key == KEY_ESC || _key == 'q' || _key == 'Q') { + // stop transport + gazebo::transport::stop(); + gazebo::transport::fini(); exit(0); } else if (_key == KEY_TAB) @@ -167,9 +194,6 @@ void GlutInitCamera(gz::CameraPtr _camera) ////////////////////////////////////////////////// void GlutInitContext() { - int argc = 0; - char **argv = 0; - glutInit(&argc, argv); glutInitDisplayMode(GLUT_DOUBLE); glutInitWindowPosition(0, 0); glutInitWindowSize(imgw, imgh); diff --git a/examples/gazebo_scene_viewer/GazeboDemo.cc b/examples/gazebo_scene_viewer/GazeboDemo.cc index 1ddd0bfce..752628425 100644 --- a/examples/gazebo_scene_viewer/GazeboDemo.cc +++ b/examples/gazebo_scene_viewer/GazeboDemo.cc @@ -14,6 +14,16 @@ * limitations under the License. * */ + +#if defined(__APPLE__) + #include + #include +#elif not defined(_WIN32) + #include + #include + #include +#endif + #include #include #include @@ -76,13 +86,23 @@ CameraPtr CreateCamera(const std::string &_engine) return camera; } -int main(int, char**) +int main(int _argc, char** _argv) { + glutInit(&_argc, _argv); + + // Expose engine name to command line because we can't instantiate both + // ogre and ogre2 at the same time + std::string ogreEngine("ogre"); + if (_argc > 1) + { + ogreEngine = _argv[1]; + } + Connect(); std::vector cameras; std::vector engineNames; - engineNames.push_back("ogre"); + engineNames.push_back(ogreEngine); engineNames.push_back("optix"); for (auto engineName : engineNames) diff --git a/examples/gazebo_scene_viewer/GazeboWorldDemo.cc b/examples/gazebo_scene_viewer/GazeboWorldDemo.cc index d792062d1..e498e2358 100644 --- a/examples/gazebo_scene_viewer/GazeboWorldDemo.cc +++ b/examples/gazebo_scene_viewer/GazeboWorldDemo.cc @@ -14,6 +14,16 @@ * limitations under the License. * */ + +#if defined(__APPLE__) + #include + #include +#elif not defined(_WIN32) + #include + #include + #include +#endif + #include #include #include @@ -76,13 +86,23 @@ CameraPtr CreateCamera(const std::string &_engine) return camera; } -int main(int, char**) +int main(int _argc, char** _argv) { + glutInit(&_argc, _argv); + + // Expose engine name to command line because we can't instantiate both + // ogre and ogre2 at the same time + std::string ogreEngine("ogre"); + if (_argc > 1) + { + ogreEngine = _argv[1]; + } + Connect(); std::vector cameras; std::vector engineNames; - engineNames.push_back("ogre"); + engineNames.push_back(ogreEngine); engineNames.push_back("optix"); for (auto engineName : engineNames) diff --git a/examples/gazebo_scene_viewer/SceneManager.cc b/examples/gazebo_scene_viewer/SceneManager.cc index 9847e1050..088cea420 100644 --- a/examples/gazebo_scene_viewer/SceneManager.cc +++ b/examples/gazebo_scene_viewer/SceneManager.cc @@ -40,6 +40,7 @@ SceneManager::SceneManager() : ////////////////////////////////////////////////// SceneManager::~SceneManager() { + this->Fini(); delete this->pimpl; } @@ -157,8 +158,8 @@ SceneManagerPrivate::SceneManagerPrivate() : ////////////////////////////////////////////////// SceneManagerPrivate::~SceneManagerPrivate() { - delete currentSceneManager; - delete newSceneManager; + newSceneManager.reset(); + currentSceneManager.reset(); } ////////////////////////////////////////////////// @@ -224,7 +225,11 @@ void SceneManagerPrivate::Init() ////////////////////////////////////////////////// void SceneManagerPrivate::Fini() { - // TODO(anyone): disconnect + // block all message receival during cleanup + std::lock_guard generalLock(this->generalMutex); + std::lock_guard poseLock(this->poseMutex); + + this->transportNode->Fini(); } ////////////////////////////////////////////////// @@ -456,6 +461,11 @@ void SceneManagerPrivate::OnLightUpdate(::ConstLightPtr &_lightMsg) // wait for update unlock before adding message std::lock_guard lock(this->generalMutex); + if (this->currentSceneManager == nullptr || this->newSceneManager == nullptr) + { + return; + } + this->currentSceneManager->OnLightUpdate(_lightMsg); this->newSceneManager->OnLightUpdate(_lightMsg); } @@ -466,6 +476,11 @@ void SceneManagerPrivate::OnModelUpdate(::ConstModelPtr &_modelMsg) // wait for update unlock before adding message std::lock_guard lock(this->generalMutex); + if (this->currentSceneManager == nullptr || this->newSceneManager == nullptr) + { + return; + } + this->currentSceneManager->OnModelUpdate(_modelMsg); this->newSceneManager->OnModelUpdate(_modelMsg); } @@ -476,6 +491,11 @@ void SceneManagerPrivate::OnJointUpdate(::ConstJointPtr &_jointMsg) // wait for update unlock before adding message std::lock_guard lock(this->generalMutex); + if (this->currentSceneManager == nullptr || this->newSceneManager == nullptr) + { + return; + } + this->currentSceneManager->OnJointUpdate(_jointMsg); this->newSceneManager->OnJointUpdate(_jointMsg); } @@ -486,6 +506,11 @@ void SceneManagerPrivate::OnVisualUpdate(::ConstVisualPtr &_visualMsg) // wait for update unlock before adding message std::lock_guard lock(this->generalMutex); + if (this->currentSceneManager == nullptr || this->newSceneManager == nullptr) + { + return; + } + this->currentSceneManager->OnVisualUpdate(_visualMsg); this->newSceneManager->OnVisualUpdate(_visualMsg); } @@ -496,6 +521,11 @@ void SceneManagerPrivate::OnSensorUpdate(::ConstSensorPtr &_sensorMsg) // wait for update unlock before adding message std::lock_guard lock(this->generalMutex); + if (this->currentSceneManager == nullptr || this->newSceneManager == nullptr) + { + return; + } + this->currentSceneManager->OnSensorUpdate(_sensorMsg); this->newSceneManager->OnSensorUpdate(_sensorMsg); } @@ -506,6 +536,11 @@ void SceneManagerPrivate::OnPoseUpdate(::ConstPosesStampedPtr &_posesMsg) // wait for update unlock before adding message std::lock_guard lock(this->poseMutex); + if (this->currentSceneManager == nullptr || this->newSceneManager == nullptr) + { + return; + } + this->currentSceneManager->OnPoseUpdate(_posesMsg); this->newSceneManager->OnPoseUpdate(_posesMsg); } @@ -516,6 +551,11 @@ void SceneManagerPrivate::OnRemovalUpdate(const std::string &_name) // wait for update unlock before adding message std::lock_guard lock(this->poseMutex); + if (this->currentSceneManager == nullptr || this->newSceneManager == nullptr) + { + return; + } + this->currentSceneManager->OnRemovalUpdate(_name); this->newSceneManager->OnRemovalUpdate(_name); } diff --git a/examples/gazebo_scene_viewer/SceneManagerPrivate.hh b/examples/gazebo_scene_viewer/SceneManagerPrivate.hh index 5b1dbc3d8..f1e85c217 100644 --- a/examples/gazebo_scene_viewer/SceneManagerPrivate.hh +++ b/examples/gazebo_scene_viewer/SceneManagerPrivate.hh @@ -20,6 +20,7 @@ #include #include #include +#include #include @@ -110,9 +111,9 @@ namespace ignition private: void DemoteCurrentScenes(); - private: CurrentSceneManager *currentSceneManager; + private: std::unique_ptr currentSceneManager; - private: NewSceneManager *newSceneManager; + private: std::unique_ptr newSceneManager; private: gazebo::transport::NodePtr transportNode; From 93539bde011df75991caf89a9b32e9664570dc9c Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Tue, 9 Mar 2021 11:25:27 -0800 Subject: [PATCH 07/12] Master branch updates (#268) Signed-off-by: Louise Poubel --- .github/workflows/ci.yml | 2 +- README.md | 11 +++++------ 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 7aa80d0bd..705db4f35 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -11,7 +11,7 @@ jobs: uses: actions/checkout@v2 - name: Compile and test id: ci - uses: ignition-tooling/action-ignition-ci@master + uses: ignition-tooling/action-ignition-ci@bionic with: codecov-token: ${{ secrets.CODECOV_TOKEN }} focal-ci: diff --git a/README.md b/README.md index 3fb9983ab..4415e1874 100644 --- a/README.md +++ b/README.md @@ -9,10 +9,9 @@ Build | Status -- | -- -Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/master/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/default) -Ubuntu Xenial | [![](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-master-xenial-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-master-xenial-amd64/) -Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-master-bionic-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-master-bionic-amd64) -Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-master-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-master-homebrew-amd64) +Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/ign-rendering3/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-rendering/branch/default) +Ubuntu Bionic | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-ign-rendering3-bionic-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-ign-rendering3-bionic-amd64) +Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_rendering-ci-ign-rendering3-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_rendering-ci-ign-rendering3-homebrew-amd64) Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ign_rendering-ci-win)](https://build.osrfoundation.org/job/ign_rendering-ci-win) Ignition Rendering is a C++ library designed to provide an abstraction @@ -87,7 +86,7 @@ Please see # Code of Conduct Please see -[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/master/CODE_OF_CONDUCT.md). +[CODE_OF_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md). # Versioning @@ -95,4 +94,4 @@ This library uses [Semantic Versioning](https://semver.org/). Additionally, this # License -This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-rendering/blob/master/LICENSE) file. +This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-rendering/blob/main/LICENSE) file. From 108e28b9f75f7c39a23f930ec6a907819c1cb758 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Fri, 12 Mar 2021 23:11:47 -0800 Subject: [PATCH 08/12] Expose particle scatter ratio parameter (#269) * expose particle scatter ratio param Signed-off-by: Ian Chen * codecheck Signed-off-by: Ian Chen * test fix Signed-off-by: Ian Chen * address review comments Signed-off-by: Ian Chen * documentation tweaks Signed-off-by: Ashton Larkin * testing Signed-off-by: Ian Chen * testing particle depth on actions Signed-off-by: Ian Chen * testing Signed-off-by: Ian Chen * revert changes, fix test Signed-off-by: Ian Chen Co-authored-by: Ashton Larkin --- ogre2/src/Ogre2DepthCamera.cc | 6 --- ogre2/src/Ogre2GpuRays.cc | 6 --- ogre2/src/Ogre2ParticleEmitter.cc | 3 ++ ogre2/src/Ogre2ParticleNoiseListener.cc | 64 ++++++++++++++++++++++- ogre2/src/Ogre2ParticleNoiseListener.hh | 15 ++++++ src/ParticleEmitter_TEST.cc | 13 +++++ test/integration/depth_camera.cc | 68 ++++++++++++++++++++++++- test/integration/gpu_rays.cc | 50 +++++++++++++++++- 8 files changed, 209 insertions(+), 16 deletions(-) diff --git a/ogre2/src/Ogre2DepthCamera.cc b/ogre2/src/Ogre2DepthCamera.cc index 3d24c10a9..67099b34f 100644 --- a/ogre2/src/Ogre2DepthCamera.cc +++ b/ogre2/src/Ogre2DepthCamera.cc @@ -134,10 +134,6 @@ class ignition::rendering::Ogre2DepthCameraPrivate /// \brief standard deviation of particle noise public: double particleStddev = 0.01; - /// \brief Particle scatter ratio. This is used to determine the ratio of - /// particles that will detected by the depth camera - public: double particleScatterRatio = 0.65; - /// \brief Listener for setting particle noise value based on particle /// emitter region public: std::unique_ptr particleNoiseListener; @@ -436,8 +432,6 @@ void Ogre2DepthCamera::CreateDepthTexture() psParams->setNamedConstant("backgroundColor", bg); psParams->setNamedConstant("particleStddev", static_cast(this->dataPtr->particleStddev)); - psParams->setNamedConstant("particleScatterRatio", - static_cast(this->dataPtr->particleScatterRatio)); std::string matDepthFinalName = "DepthCameraFinal"; Ogre::MaterialPtr matDepthFinal = diff --git a/ogre2/src/Ogre2GpuRays.cc b/ogre2/src/Ogre2GpuRays.cc index effc70192..b0bc9ff28 100644 --- a/ogre2/src/Ogre2GpuRays.cc +++ b/ogre2/src/Ogre2GpuRays.cc @@ -169,10 +169,6 @@ class ignition::rendering::Ogre2GpuRaysPrivate /// \brief standard deviation of particle noise public: double particleStddev = 0.01; - /// \brief Particle scatter ratio. This is used to determine the ratio of - /// particles that will detected by the depth camera - public: double particleScatterRatio = 0.65; - /// \brief Listener for setting particle noise value based on particle /// emitter region public: std::unique_ptr particleNoiseListener[6]; @@ -623,8 +619,6 @@ void Ogre2GpuRays::Setup1stPass() static_cast(this->dataMinVal)); psParams->setNamedConstant("particleStddev", static_cast(this->dataPtr->particleStddev)); - psParams->setNamedConstant("particleScatterRatio", - static_cast(this->dataPtr->particleScatterRatio)); // Create 1st pass compositor auto engine = Ogre2RenderEngine::Instance(); diff --git a/ogre2/src/Ogre2ParticleEmitter.cc b/ogre2/src/Ogre2ParticleEmitter.cc index 31ebfdd6a..382f192fd 100644 --- a/ogre2/src/Ogre2ParticleEmitter.cc +++ b/ogre2/src/Ogre2ParticleEmitter.cc @@ -479,6 +479,9 @@ void Ogre2ParticleEmitter::CreateParticleSystem() { // Instantiate the particle system and default parameters. this->dataPtr->ps = this->scene->OgreSceneManager()->createParticleSystem(); + this->dataPtr->ps->getUserObjectBindings().setUserAny( + Ogre::Any(this->Id())); + this->dataPtr->ps->setCullIndividually(true); this->dataPtr->ps->setParticleQuota(500); this->dataPtr->ps->setSortingEnabled(true); diff --git a/ogre2/src/Ogre2ParticleNoiseListener.cc b/ogre2/src/Ogre2ParticleNoiseListener.cc index 67e29cf37..ebf392118 100644 --- a/ogre2/src/Ogre2ParticleNoiseListener.cc +++ b/ogre2/src/Ogre2ParticleNoiseListener.cc @@ -1,5 +1,5 @@ /* - * Copyright (C) 2020 Open Source Robotics Foundation + * Copyright (C) 2021 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -15,9 +15,12 @@ * */ +#include + #include "ignition/rendering/ogre2/Ogre2Includes.hh" #include "ignition/rendering/ogre2/Ogre2RenderTypes.hh" #include "ignition/rendering/ogre2/Ogre2Scene.hh" +#include "ignition/rendering/ogre2/Ogre2Visual.hh" #include "Ogre2ParticleNoiseListener.hh" @@ -82,6 +85,65 @@ void Ogre2ParticleNoiseListener::preRenderTargetUpdate( pass->getFragmentProgramParameters(); psParams->setNamedConstant("particleStddev", static_cast(particleStddev)); + + // get particle scatter ratio value from particle emitter user data + // and pass that to the shaders + Ogre::Any userAny = ps->getUserObjectBindings().getUserAny(); + if (!userAny.isEmpty() && userAny.getType() == typeid(unsigned int)) + { + VisualPtr result; + try + { + result = this->scene->VisualById( + Ogre::any_cast(userAny)); + } + catch(Ogre::Exception &e) + { + ignerr << "Ogre Error:" << e.getFullDescription() << "\n"; + } + Ogre2VisualPtr ogreVisual = + std::dynamic_pointer_cast(result); + if (ogreVisual) + { + const std::string particleScatterRatioKey = "particle_scatter_ratio"; + Variant particleScatterRatioAny = + ogreVisual->UserData(particleScatterRatioKey); + if (particleScatterRatioAny.index() != std::variant_npos) + { + float ratio = -1.0; + try + { + ratio = std::get(particleScatterRatioAny); + } + catch(...) + { + try + { + ratio = std::get(particleScatterRatioAny); + } + catch(...) + { + try + { + ratio = std::get(particleScatterRatioAny); + } + catch(std::bad_variant_access &e) + { + ignerr << "Error casting user data: " << e.what() << "\n"; + ratio = -1.0; + } + } + } + if (ratio > 0) + { + this->particleScatterRatio = ratio; + } + } + } + } + psParams->setNamedConstant("particleScatterRatio", + static_cast(this->particleScatterRatio)); + return; } itor.moveNext(); diff --git a/ogre2/src/Ogre2ParticleNoiseListener.hh b/ogre2/src/Ogre2ParticleNoiseListener.hh index 1c4db2e54..52800be28 100644 --- a/ogre2/src/Ogre2ParticleNoiseListener.hh +++ b/ogre2/src/Ogre2ParticleNoiseListener.hh @@ -40,9 +40,24 @@ namespace ignition private: virtual void preRenderTargetUpdate( const Ogre::RenderTargetEvent &_evt) override; + /// \brief Pointer to scene private: Ogre2ScenePtr scene; + + /// \brief Pointer to camera private: Ogre::Camera *ogreCamera = nullptr; + + /// \brief Pointer to ogre matieral with shaders for applying particle + /// scattering effect to sensors private: Ogre::MaterialPtr ogreMaterial; + + /// \brief Particle scatter ratio. This is used to determine the ratio of + /// particles that will be detected by sensors. Increasing the ratio + /// increases the scatter of the particles, which means there is a higher + /// chance of particles reflecting and interfering with depth sensing, + /// making the emitter appear more dense. Decreasing the ratio decreases + /// the scatter of the particles, making it appear less dense. This value + /// should be > 0. + private: float particleScatterRatio = 0.65f; }; } } diff --git a/src/ParticleEmitter_TEST.cc b/src/ParticleEmitter_TEST.cc index 6269da672..de1049343 100644 --- a/src/ParticleEmitter_TEST.cc +++ b/src/ParticleEmitter_TEST.cc @@ -91,6 +91,11 @@ void ParticleEmitterTest::CheckBasicAPI() math::Color expectedColorEnd = ignition::math::Color::White; double expectedScaleRate = 1; std::string expectedColorRangeImage = ""; + // Particle scatter ratio is stored in user data + // TODO(anyone) Add API to set scatter ratio + // (this requires adding a virtual function in the base class, + // which breaks ABI, so this should be done in an unreleased version) + Variant emptyVariant; // Check default expectations. EXPECT_EQ(expectedEmitterType, particleEmitter->Type()); @@ -107,6 +112,7 @@ void ParticleEmitterTest::CheckBasicAPI() EXPECT_EQ(expectedColorEnd, particleEmitter->ColorEnd()); EXPECT_DOUBLE_EQ(expectedScaleRate, particleEmitter->ScaleRate()); EXPECT_EQ(expectedColorRangeImage, particleEmitter->ColorRangeImage()); + EXPECT_EQ(emptyVariant, particleEmitter->UserData("particle_scatter_ratio")); // Modify values. expectedEmitterType = EmitterType::EM_BOX; @@ -123,6 +129,10 @@ void ParticleEmitterTest::CheckBasicAPI() expectedColorEnd = ignition::math::Color::Blue; expectedScaleRate = 10; expectedColorRangeImage = common::joinPaths(TEST_MEDIA_PATH, "texture.png"); + // Particle scatter ratio is stored in user data + // TODO(anyone) Add API to set scatter ratio + // (see note above in the other todo about how this breaks ABI) + double expectedScatterRatio = 0.24; // Modify attributes. particleEmitter->SetType(expectedEmitterType); @@ -137,6 +147,7 @@ void ParticleEmitterTest::CheckBasicAPI() particleEmitter->SetColorRange(expectedColorStart, expectedColorEnd); particleEmitter->SetScaleRate(expectedScaleRate); particleEmitter->SetColorRangeImage(expectedColorRangeImage); + particleEmitter->SetUserData("particle_scatter_ratio", expectedScatterRatio); // Check getters. EXPECT_EQ(expectedEmitterType, particleEmitter->Type()); @@ -153,6 +164,8 @@ void ParticleEmitterTest::CheckBasicAPI() EXPECT_EQ(expectedColorEnd, particleEmitter->ColorEnd()); EXPECT_DOUBLE_EQ(expectedScaleRate, particleEmitter->ScaleRate()); EXPECT_EQ(expectedColorRangeImage, particleEmitter->ColorRangeImage()); + Variant v = particleEmitter->UserData("particle_scatter_ratio"); + EXPECT_DOUBLE_EQ(expectedScatterRatio, std::get(v)); } ///////////////////////////////////////////////// diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index 5794ec885..2fbfd50e9 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -598,15 +598,18 @@ void DepthCameraTest::DepthCameraParticles( // create particle emitter between depth camera and box ignition::math::Vector3d particlePosition(1.0, 0, 0); + ignition::math::Quaterniond particleRotation( + ignition::math::Vector3d(0, -1.57, 0)); ignition::math::Vector3d particleSize(0.2, 0.2, 0.2); ignition::rendering::ParticleEmitterPtr emitter = scene->CreateParticleEmitter(); emitter->SetLocalPosition(particlePosition); + emitter->SetLocalRotation(particleRotation); emitter->SetParticleSize(particleSize); emitter->SetRate(100); emitter->SetLifetime(2); emitter->SetVelocityRange(0.1, 0.1); - emitter->SetScaleRate(0.1); + emitter->SetScaleRate(0.0); emitter->SetColorRange(ignition::math::Color::Red, ignition::math::Color::Black); emitter->SetEmitting(true); @@ -678,6 +681,69 @@ void DepthCameraTest::DepthCameraParticles( EXPECT_LT(pointParticleAvg, pointAvg); EXPECT_LT(depthParticleAvg, depthAvg); + // test setting particle scatter ratio + // reduce particle scatter ratio - this creates a "less dense" particle + // emitter so we should have larger depth values on avg since fewers + // depth readings are occluded by particles + emitter->SetUserData("particle_scatter_ratio", 0.1); + + g_depthCounter = 0u; + g_pointCloudCounter = 0u; + for (unsigned int i = 0; i < 100; ++i) + { + depthCamera->Update(); + } + EXPECT_EQ(100u, g_depthCounter); + EXPECT_EQ(100u, g_pointCloudCounter); + + double pointParticleLowScatterAvg = 0.0; + double depthParticleLowScatterAvg = 0.0; + + // Verify depth and point cloud data after setting particle scatter ratio + for (unsigned int i = 0u; i < depthCamera->ImageHeight(); ++i) + { + unsigned int step = + i * depthCamera->ImageWidth() * pointCloudChannelCount; + for (unsigned int j = 0u; j < depthCamera->ImageWidth(); ++j) + { + float x = pointCloudData[step + j * pointCloudChannelCount]; + float y = pointCloudData[step + j * pointCloudChannelCount + 1]; + float z = pointCloudData[step + j * pointCloudChannelCount + 2]; + + double xd = static_cast(x); + // depth camera sees only certain percentage of particles + // so the values should be either + // * box depth (depth camera does not see particles), or + // * noisy particle depth (depth camera see particles but values + // are affected by noise) + EXPECT_TRUE( + ignition::math::equal(expectedParticleDepth, xd, depthNoiseTol) || + ignition::math::equal(expectedDepth, xd, DEPTH_TOL)) + << "actual vs expected particle depth: " + << xd << " vs " << expectedParticleDepth; + float depth = scan[i * depthCamera->ImageWidth() + j]; + double depthd = static_cast(depth); + EXPECT_TRUE( + ignition::math::equal(expectedParticleDepth, depthd, depthNoiseTol) + || ignition::math::equal(expectedDepth, depthd, DEPTH_TOL)) + << "actual vs expected particle depth: " + << depthd << " vs " << expectedParticleDepth; + + pointParticleLowScatterAvg += + ignition::math::Vector3d(x, y, z).Length(); + depthParticleLowScatterAvg += depthd; + } + } + + // compare point and depth data before and after setting particle scatter + // ratio. The avg point length and depth values in the image with low + // particle scatter ratio should be should be higher than the previous + // images with particle effects + pointParticleLowScatterAvg /= pixelCount; + depthParticleLowScatterAvg /= pixelCount; + EXPECT_LT(pointParticleAvg, pointParticleLowScatterAvg); + EXPECT_LT(depthParticleAvg, depthParticleLowScatterAvg); + // Clean up connection.reset(); delete [] scan; diff --git a/test/integration/gpu_rays.cc b/test/integration/gpu_rays.cc index a8b751dc2..0db85ec79 100644 --- a/test/integration/gpu_rays.cc +++ b/test/integration/gpu_rays.cc @@ -484,7 +484,7 @@ void GpuRaysTest::RaysParticles(const std::string &_renderEngine) const double hMinAngle = -IGN_PI / 2.0; const double hMaxAngle = IGN_PI / 2.0; - const double minRange = 0.1; + const double minRange = 0.12; const double maxRange = 10.0; const int hRayCount = 320; const int vRayCount = 1; @@ -550,15 +550,18 @@ void GpuRaysTest::RaysParticles(const std::string &_renderEngine) // create particle emitter between sensor and box in the center ignition::math::Vector3d particlePosition(1.0, 0, 0); + ignition::math::Quaterniond particleRotation( + ignition::math::Vector3d(0, -1.57, 0)); ignition::math::Vector3d particleSize(0.2, 0.2, 0.2); ignition::rendering::ParticleEmitterPtr emitter = scene->CreateParticleEmitter(); emitter->SetLocalPosition(particlePosition); + emitter->SetLocalRotation(particleRotation); emitter->SetParticleSize(particleSize); emitter->SetRate(100); emitter->SetLifetime(2); emitter->SetVelocityRange(0.1, 0.1); - emitter->SetScaleRate(0.1); + emitter->SetScaleRate(0.0); emitter->SetColorRange(ignition::math::Color::Red, ignition::math::Color::Black); emitter->SetEmitting(true); @@ -621,6 +624,49 @@ void GpuRaysTest::RaysParticles(const std::string &_renderEngine) // there should be at least one miss EXPECT_GT(particleMissCount, 0u); + + // test setting particle scatter ratio + // reduce particle scatter ratio - this creates a "less dense" particle + // emitter so we should have larger range values on avg since fewer + // rays are occluded by particles + emitter->SetUserData("particle_scatter_ratio", 0.1); + + unsigned int particleHitLowScatterCount = 0u; + unsigned int particleMissLowScatterCount = 0u; + for (unsigned int i = 0u; i < 100u; ++i) + { + gpuRays->Update(); + + // sensor should see ether a particle or box01 + double particleRange = static_cast(scan[mid]); + bool particleHit = ignition::math::equal( + expectedParticleRange, particleRange, laserNoiseTol); + bool particleMiss = ignition::math::equal( + expectedRangeAtMidPointBox1, particleRange, LASER_TOL); + EXPECT_TRUE(particleHit || particleMiss) + << "actual vs expected particle range: " + << particleRange << " vs " << expectedParticleRange; + + particleHitLowScatterCount += particleHit ? 1u : 0u; + particleMissLowScatterCount += particleMiss ? 1u : 0u; + + // sensor should see box02 without noise or scatter effect + EXPECT_NEAR(expectedRangeAtMidPointBox2, scan[0], LASER_TOL); + + // sensor should not see box03 as it is out of range + EXPECT_DOUBLE_EQ(ignition::math::INF_D, scan[last]); + } + + // there should be at least one hit + EXPECT_GT(particleHitLowScatterCount, 0u); + // there should be at least one miss + EXPECT_GT(particleMissLowScatterCount, 0u); + + // there should be more misses than the previous particle emitter setting + // i.e. more rays missing the particles because of low scatter ratio / density + EXPECT_GT(particleHitCount, particleHitLowScatterCount); + EXPECT_LT(particleMissCount, particleMissLowScatterCount); + c.reset(); delete [] scan; From 7d55d9b24a805875258975cb7d48c072e3a55493 Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Sat, 13 Mar 2021 00:21:35 -0800 Subject: [PATCH 09/12] fix overriding blend mode (#266) Signed-off-by: Ian Chen --- include/ignition/rendering/base/BaseMaterial.hh | 3 ++- ogre2/src/Ogre2Material.cc | 3 +-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/include/ignition/rendering/base/BaseMaterial.hh b/include/ignition/rendering/base/BaseMaterial.hh index f77200659..8d6907e3c 100644 --- a/include/ignition/rendering/base/BaseMaterial.hh +++ b/include/ignition/rendering/base/BaseMaterial.hh @@ -873,9 +873,10 @@ namespace ignition this->SetSpecular(_material->Specular()); this->SetEmissive(_material->Emissive()); this->SetShininess(_material->Shininess()); - this->SetTransparency(_material->Transparency()); this->SetAlphaFromTexture(_material->TextureAlphaEnabled(), _material->AlphaThreshold(), _material->TwoSidedEnabled()); + // override transparency / blend setting after setting alpha from texture + this->SetTransparency(_material->Transparency()); // override depth check / depth write after setting transparency this->SetDepthCheckEnabled(_material->DepthCheckEnabled()); this->SetDepthWriteEnabled(_material->DepthWriteEnabled()); diff --git a/ogre2/src/Ogre2Material.cc b/ogre2/src/Ogre2Material.cc index c57189116..73ba89919 100644 --- a/ogre2/src/Ogre2Material.cc +++ b/ogre2/src/Ogre2Material.cc @@ -157,17 +157,16 @@ void Ogre2Material::SetAlphaFromTexture(bool _enabled, double _alpha, bool _twoSided) { BaseMaterial::SetAlphaFromTexture(_enabled, _alpha, _twoSided); - Ogre::HlmsBlendblock block; if (_enabled) { this->ogreDatablock->setAlphaTest(Ogre::CMPF_GREATER_EQUAL); + Ogre::HlmsBlendblock block; block.setBlendType(Ogre::SBT_TRANSPARENT_ALPHA); this->ogreDatablock->setBlendblock(block); } else { this->ogreDatablock->setAlphaTest(Ogre::CMPF_ALWAYS_PASS); - this->ogreDatablock->setBlendblock(block); } this->ogreDatablock->setAlphaTestThreshold(_alpha); this->ogreDatablock->setTwoSidedLighting(_twoSided); From e3d56ad17a19069792ec14351a83843fbe06de8f Mon Sep 17 00:00:00 2001 From: Ian Chen Date: Tue, 16 Mar 2021 10:23:31 -0700 Subject: [PATCH 10/12] Fix DepthGaussianNoise test (#271) Signed-off-by: Ian Chen --- test/integration/render_pass.cc | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/test/integration/render_pass.cc b/test/integration/render_pass.cc index 17659a3e3..a5cc16dd8 100644 --- a/test/integration/render_pass.cc +++ b/test/integration/render_pass.cc @@ -339,8 +339,9 @@ void RenderPassTest::DepthGaussianNoise(const std::string &_renderEngine) float mz = pointCloudData[pcMid + 2]; float midLeftZ = pointCloudData[pcMid + 2 - pointCloudChannelCount]; float midRightZ = pointCloudData[pcMid + 2 + pointCloudChannelCount]; - EXPECT_NEAR(mz, midLeftZ, noiseTol); - EXPECT_NEAR(mz, midRightZ, noiseTol); + // 2 noisy values should be within 2 * 4 sigma + EXPECT_NEAR(mz, midLeftZ, 2*noiseTol); + EXPECT_NEAR(mz, midRightZ, 2*noiseTol); // Verify Point Cloud RGB values // The mid point should be blue From 3454c148f920b6028775aa2d49e96a424221ce54 Mon Sep 17 00:00:00 2001 From: Ashton Larkin Date: Wed, 10 Feb 2021 12:47:43 -0500 Subject: [PATCH 11/12] Handle non-positive object temperatures (#243) Signed-off-by: Ashton Larkin Signed-off-by: Ian Chen --- ogre2/src/Ogre2ThermalCamera.cc | 39 +++++++++++-------- .../materials/programs/thermal_camera_fs.glsl | 29 +++++++------- 2 files changed, 36 insertions(+), 32 deletions(-) diff --git a/ogre2/src/Ogre2ThermalCamera.cc b/ogre2/src/Ogre2ThermalCamera.cc index eaac4647e..18683c7c3 100644 --- a/ogre2/src/Ogre2ThermalCamera.cc +++ b/ogre2/src/Ogre2ThermalCamera.cc @@ -266,6 +266,7 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( if (tempAny.index() != 0 && !std::holds_alternative(tempAny)) { float temp = -1.0; + bool foundTemp = true; try { temp = std::get(tempAny); @@ -286,30 +287,36 @@ void Ogre2ThermalCameraMaterialSwitcher::preRenderTargetUpdate( { ignerr << "Error casting user data: " << e.what() << "\n"; temp = -1.0; + foundTemp = false; } } } - // only accept positive temperature (in kelvin) - if (temp >= 0.0) + // if a non-positive temperature was given, clamp it to 0 + if (foundTemp && temp < 0.0) { - for (unsigned int i = 0; i < item->getNumSubItems(); ++i) - { - Ogre::SubItem *subItem = item->getSubItem(i); + temp = 0.0; + ignwarn << "Unable to set negatve temperature for: " + << ogreVisual->Name() << ". Value cannot be lower than absolute " + << "zero. Clamping temperature to 0 degrees Kelvin." + << std::endl; + } + 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); + // 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; + // 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; - subItem->setMaterial(this->heatSourceMaterial); - } + subItem->setMaterial(this->heatSourceMaterial); } } // get heat signature and the corresponding min/max temperature values diff --git a/ogre2/src/media/materials/programs/thermal_camera_fs.glsl b/ogre2/src/media/materials/programs/thermal_camera_fs.glsl index f5134f28c..21b6ddc55 100644 --- a/ogre2/src/media/materials/programs/thermal_camera_fs.glsl +++ b/ogre2/src/media/materials/programs/thermal_camera_fs.glsl @@ -71,29 +71,26 @@ void main() bool isHeatSource = (rgba.g == 0.0 && rgba.b == 0.0 && rgba.a == 0.0); float heat = rgba.r; - if (heat > 0.0) + if (isHeatSource) { - if (isHeatSource) - { - // heat is normalized so convert back to work in kelvin - // for 16 bit camera and 0.01 resolution: - // ((1 << bitDepth) - 1) * resolution = 655.35 - temp = heat * bitMaxValue * resolution; + // heat is normalized so convert back to work in kelvin + // 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; - } - else - { - // other non-heat source objects are assigned ambient temperature - temp = ambient; - } + // set temperature variation for heat source + heatRange = heatSourceTempRange; + } + else + { + // other non-heat source objects are assigned ambient temperature + temp = ambient; } // add temperature variation, either as a function of color or depth if (rgbToTemp == 1) { - if (heat > 0.0 && !isHeatSource) + if (!isHeatSource) { // convert to grayscale: darker = warmer // (https://docs.opencv.org/3.4/de/d25/imgproc_color_conversions.html) From d98ea2abeef5c1927ff01b7ed2715a33c493491a Mon Sep 17 00:00:00 2001 From: Ashton Larkin Date: Wed, 17 Mar 2021 15:41:09 -0400 Subject: [PATCH 12/12] 4.7.0 (#274) Signed-off-by: Ashton Larkin --- CMakeLists.txt | 2 +- Changelog.md | 23 +++++++++++++++++++++++ 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 028b47109..86dd830dc 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR) #============================================================================ # Initialize the project #============================================================================ -project(ignition-rendering4 VERSION 4.6.0) +project(ignition-rendering4 VERSION 4.7.0) #============================================================================ # Find ignition-cmake diff --git a/Changelog.md b/Changelog.md index 73375111a..3c0911f67 100644 --- a/Changelog.md +++ b/Changelog.md @@ -2,6 +2,29 @@ ### Ignition Rendering 4.X +### Ignition Rendering 4.7.0 (2021-03-17) + +1. Enable depth write in particles example + * [Pull Request #217](https://github.com/ignitionrobotics/ign-rendering/pull/217) + +1. Fix gazebo_scene_viewer for macOS and ensure clean exit + * [Pull Request #259](https://github.com/ignitionrobotics/ign-rendering/pull/259) + +1. Master branch updates + * [Pull Request #268](https://github.com/ignitionrobotics/ign-rendering/pull/268) + +1. Expose particle scatter ratio parameter + * [Pull Request #269](https://github.com/ignitionrobotics/ign-rendering/pull/269) + +1. Fix overriding blend mode + * [Pull Request #266](https://github.com/ignitionrobotics/ign-rendering/pull/266) + +1. Fix DepthGaussianNoise test + * [Pull Request #271](https://github.com/ignitionrobotics/ign-rendering/pull/271) + +1. Handle non-positive object temperatures + * [Pull Request #243](https://github.com/ignitionrobotics/ign-rendering/pull/243) + ### Ignition Rendering 4.6.0 (2021-03-01) 1. Improve particle scattering noise