Skip to content

Commit

Permalink
Expose particle scatter ratio parameter (#269)
Browse files Browse the repository at this point in the history
* expose particle scatter ratio param

Signed-off-by: Ian Chen <[email protected]>

* codecheck

Signed-off-by: Ian Chen <[email protected]>

* test fix

Signed-off-by: Ian Chen <[email protected]>

* address review comments

Signed-off-by: Ian Chen <[email protected]>

* documentation tweaks

Signed-off-by: Ashton Larkin <[email protected]>

* testing

Signed-off-by: Ian Chen <[email protected]>

* testing particle depth on actions

Signed-off-by: Ian Chen <[email protected]>

* testing

Signed-off-by: Ian Chen <[email protected]>

* revert changes, fix test

Signed-off-by: Ian Chen <[email protected]>

Co-authored-by: Ashton Larkin <[email protected]>
  • Loading branch information
iche033 and adlarkin authored Mar 13, 2021
1 parent 886d0d9 commit 108e28b
Show file tree
Hide file tree
Showing 8 changed files with 209 additions and 16 deletions.
6 changes: 0 additions & 6 deletions ogre2/src/Ogre2DepthCamera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<Ogre2ParticleNoiseListener> particleNoiseListener;
Expand Down Expand Up @@ -436,8 +432,6 @@ void Ogre2DepthCamera::CreateDepthTexture()
psParams->setNamedConstant("backgroundColor", bg);
psParams->setNamedConstant("particleStddev",
static_cast<float>(this->dataPtr->particleStddev));
psParams->setNamedConstant("particleScatterRatio",
static_cast<float>(this->dataPtr->particleScatterRatio));

std::string matDepthFinalName = "DepthCameraFinal";
Ogre::MaterialPtr matDepthFinal =
Expand Down
6 changes: 0 additions & 6 deletions ogre2/src/Ogre2GpuRays.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<Ogre2ParticleNoiseListener> particleNoiseListener[6];
Expand Down Expand Up @@ -623,8 +619,6 @@ void Ogre2GpuRays::Setup1stPass()
static_cast<float>(this->dataMinVal));
psParams->setNamedConstant("particleStddev",
static_cast<float>(this->dataPtr->particleStddev));
psParams->setNamedConstant("particleScatterRatio",
static_cast<float>(this->dataPtr->particleScatterRatio));

// Create 1st pass compositor
auto engine = Ogre2RenderEngine::Instance();
Expand Down
3 changes: 3 additions & 0 deletions ogre2/src/Ogre2ParticleEmitter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
64 changes: 63 additions & 1 deletion ogre2/src/Ogre2ParticleNoiseListener.cc
Original file line number Diff line number Diff line change
@@ -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.
Expand All @@ -15,9 +15,12 @@
*
*/

#include <string>

#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"

Expand Down Expand Up @@ -82,6 +85,65 @@ void Ogre2ParticleNoiseListener::preRenderTargetUpdate(
pass->getFragmentProgramParameters();
psParams->setNamedConstant("particleStddev",
static_cast<float>(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<unsigned int>(userAny));
}
catch(Ogre::Exception &e)
{
ignerr << "Ogre Error:" << e.getFullDescription() << "\n";
}
Ogre2VisualPtr ogreVisual =
std::dynamic_pointer_cast<Ogre2Visual>(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<float>(particleScatterRatioAny);
}
catch(...)
{
try
{
ratio = std::get<double>(particleScatterRatioAny);
}
catch(...)
{
try
{
ratio = std::get<int>(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<float>(this->particleScatterRatio));

return;
}
itor.moveNext();
Expand Down
15 changes: 15 additions & 0 deletions ogre2/src/Ogre2ParticleNoiseListener.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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;
};
}
}
Expand Down
13 changes: 13 additions & 0 deletions src/ParticleEmitter_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand All @@ -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;
Expand All @@ -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);
Expand All @@ -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());
Expand All @@ -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<double>(v));
}

/////////////////////////////////////////////////
Expand Down
68 changes: 67 additions & 1 deletion test/integration/depth_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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<double>(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<double>(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;
Expand Down
50 changes: 48 additions & 2 deletions test/integration/gpu_rays.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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<double>(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;
Expand Down

0 comments on commit 108e28b

Please sign in to comment.