Skip to content

Commit

Permalink
Merge pull request #347 from ignitionrobotics/merge_3_4_061721
Browse files Browse the repository at this point in the history
3 -> 4
  • Loading branch information
iche033 authored Jun 18, 2021
2 parents 97891ac + 0551b74 commit f208f9c
Show file tree
Hide file tree
Showing 7 changed files with 42 additions and 18 deletions.
8 changes: 4 additions & 4 deletions ogre2/src/Ogre2RenderTarget.cc
Original file line number Diff line number Diff line change
Expand Up @@ -331,10 +331,10 @@ void Ogre2RenderTarget::UpdateRenderPassChain(
ogre2RenderPass->OgreCompositorNodeDefinitionName());

// check if we need to create all nodes or just update the connections.
// if node does not exist then it means it has not been added to the
// chain yet, in which case, we need to recreate the nodes and
// connections
if (!node)
// if node does not exist then it means it either has not been added to
// the chain yet or it was removed because it was disabled.
// In both cases, we need to recreate the nodes and connections
if (!node && ogre2RenderPass->IsEnabled())
{
_recreateNodes = true;
}
Expand Down
7 changes: 5 additions & 2 deletions ogre2/src/Ogre2SelectionBuffer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -175,9 +175,12 @@ void Ogre2SelectionBuffer::CreateRTTBuffer()
const_cast<Ogre::CompositorPassSceneDef *>(scenePass)->mVisibilityMask =
IGN_VISIBILITY_SELECTABLE;

// buffer to store render texture data
size_t bufferSize = Ogre::PixelUtil::getMemorySize(width, height, 1, format);
// buffer to store render texture data. Ensure it's at least 4 bytes
size_t bufferSize = std::max<size_t>(
Ogre::PixelUtil::getMemorySize(width, height, 1, format),
4u);
this->dataPtr->buffer = new uint8_t[bufferSize];
memset(this->dataPtr->buffer, 0, 4u);
this->dataPtr->pixelBox = new Ogre::PixelBox(width,
height, 1, format, this->dataPtr->buffer);
}
Expand Down
10 changes: 9 additions & 1 deletion ogre2/src/media/materials/programs/depth_camera_final_fs.glsl
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,18 @@ uniform float far;
uniform float min;
uniform float max;

uniform vec4 texResolution;

void main()
{
float tolerance = 1e-6;
vec4 p = texture(inputTexture, inPs.uv0);

// Note: We use texelFetch because p.a contains an uint32 and sampling
// (even w/ point filtering) causes p.a to loss information (e.g.
// values close to 0 get rounded to 0)
//
// See https://github.com/ignitionrobotics/ign-rendering/issues/332
vec4 p = texelFetch(inputTexture, ivec2(inPs.uv0 *texResolution.xy), 0);

vec3 point = p.xyz;

Expand Down
2 changes: 2 additions & 0 deletions ogre2/src/media/materials/scripts/depth_camera.material
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,8 @@ fragment_program DepthCameraFinalFS glsl
default_params
{
param_named inputTexture int 0

param_named_auto texResolution texture_size 0
}
}

Expand Down
5 changes: 3 additions & 2 deletions src/GaussianNoisePass_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,9 @@ void GaussianNoisePassTest::GaussianNoise(const std::string &_renderEngine)
double biasStdDev = 0.007;
noisePass->SetBiasStdDev(biasStdDev);
// expect bias to be within 3-sigma
EXPECT_LE(std::fabs(noisePass->Bias()), biasMean + biasStdDev*3);
EXPECT_GE(std::fabs(noisePass->Bias()), biasMean - biasStdDev*3);
// Note, tol relaxed to 4-sigma to fix flaky test
EXPECT_LE(std::fabs(noisePass->Bias()), biasMean + biasStdDev*4);
EXPECT_GE(std::fabs(noisePass->Bias()), biasMean - biasStdDev*4);
}

/////////////////////////////////////////////////
Expand Down
12 changes: 11 additions & 1 deletion src/Image.cc
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,16 @@
using namespace ignition;
using namespace rendering;

//////////////////////////////////////////////////
template <class T>
struct ArrayDeleter
{
void operator () (T const * p)
{
delete [] p;
}
};

//////////////////////////////////////////////////
Image::Image(unsigned int _width, unsigned int _height,
PixelFormat _format) :
Expand All @@ -27,7 +37,7 @@ Image::Image(unsigned int _width, unsigned int _height,
{
this->format = PixelUtil::Sanitize(_format);
unsigned int size = this->MemorySize();
this->data = DataPtr(new unsigned char[size]);
this->data = DataPtr(new unsigned char[size], ArrayDeleter<unsigned char>());
}

//////////////////////////////////////////////////
Expand Down
16 changes: 8 additions & 8 deletions test/integration/depth_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,11 @@ void DepthCameraTest::DepthCameraBoxes(
unsigned int ma = *mrgba >> 0 & 0xFF;
EXPECT_EQ(0u, mr);
EXPECT_EQ(0u, mg);
// Note: If it fails here, it may be this problem again:
// https://github.com/ignitionrobotics/ign-rendering/issues/332
#ifndef __APPLE__
EXPECT_GT(mb, 0u);
#endif

// Far left and right points should be red (background color)
float lc = pointCloudData[pcLeft + 3];
Expand Down Expand Up @@ -453,7 +457,11 @@ void DepthCameraTest::DepthCameraBoxes(
unsigned int a = *rgba >> 0 & 0xFF;
EXPECT_EQ(0u, r);
EXPECT_EQ(0u, g);
// Note: If it fails here, it may be this problem again:
// https://github.com/ignitionrobotics/ign-rendering/issues/332
#ifndef __APPLE__
EXPECT_GT(b, 0u);
#endif
EXPECT_EQ(255u, a);
}
}
Expand Down Expand Up @@ -762,20 +770,12 @@ void DepthCameraTest::DepthCameraParticles(
ignition::rendering::unloadEngine(engine->Name());
}

#ifdef __APPLE__
TEST_P(DepthCameraTest, DISABLED_DepthCameraBoxes)
#else
TEST_P(DepthCameraTest, DepthCameraBoxes)
#endif
{
DepthCameraBoxes(GetParam());
}

#ifdef __APPLE__
TEST_P(DepthCameraTest, DISABLED_DepthCameraParticles)
#else
TEST_P(DepthCameraTest, DepthCameraParticles)
#endif
{
DepthCameraParticles(GetParam());
}
Expand Down

0 comments on commit f208f9c

Please sign in to comment.