Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

INTEGRATION_depth_camera fails with DEPTH_CLAMP disabled #395

Open
darksylinc opened this issue Sep 5, 2021 · 9 comments
Open

INTEGRATION_depth_camera fails with DEPTH_CLAMP disabled #395

darksylinc opened this issue Sep 5, 2021 · 9 comments
Labels
bug Something isn't working help wanted Extra attention is needed

Comments

@darksylinc
Copy link
Contributor

darksylinc commented Sep 5, 2021

As @iche033 noticed, this change in ogre-next caused INTEGRATION_depth_camera to fail.

However the "correct way" is to have that change, and it is currently being workarounded in ign-rendering by temporarily turning on DEPTH_CLAMP manually.

This ticket will track the causes of the bugs and fix them

Explanation of DEPTH_CLAMP

We need to first explain what DEPTH_CLAMP is. Normally when rendering a triangle whose Z (depth) is outside [near; far] range it gets clipped. i.e. it doesn't appear at all. In normalized depth the value falls outside [0; 1] range.

However when DEPTH_CLAMP is enabled; any value outside is clamped instead of getting clipped. Thus a depth of 1.2 becomes 1.0 and a depth of -0.2 gets clamped to 0 and ends up appearing on screen.

The effect visually (if you'd imagine it) would be something like this:

01

As the sphere gets closer to the camera and tries to go through it, its depth gets clamped and covers the screen:

02

INTEGRATION_depth_camera places the camera inside the cube

The following snippet:

// Check that for a box really close it returns it is not seen
ignition::math::Vector3d boxPositionNear(
    unitBoxSize * 0.5 + nearDist * 0.5, 0.0, 0.0);
box->SetLocalPosition(boxPositionNear);

Places the cube a bit too close:

03

Therefore the cube:

  1. If DEPTH_CLAMP is disabled, it won't be rendered due to backface culling (correct behavior). The final colour is red because of the background.
  2. If DEPTH_CLAMP is enabled, it will be rendered due to the face behind the camera getting clamped to be on screen. The final colour is blue, which is the colour of the cube.

Later when the postprocess shader is run:

  1. With DEPTH_CLAMP disabled; it will see depth is at +INF, colour is already red and does nothing
  2. With DEPTH_CLAMP enabled; it will see depth is behind the near plane, thus it sets the depth to -INF to signal this situation; and override the blue colour with the background colour red.

And this is why the test fails. As it expects red colour (due to the postprocess shader override) but it expects depth to be at -inf instead of +inf:

// Verify Depth
// box not detected
EXPECT_FLOAT_EQ(minVal, scan[mid]);
EXPECT_FLOAT_EQ(minVal, scan[left]);
EXPECT_FLOAT_EQ(minVal, scan[right]);

// Verify Point Cloud XYZ
{
  // all points should be min val
  for (unsigned int i = 0; i < depthCamera->ImageHeight(); ++i)
  {
    unsigned int step = i*depthCamera->ImageWidth()*pointCloudChannelCount;
    for (unsigned int j = 0; j < depthCamera->ImageWidth(); ++j)
    {
      float x = pointCloudData[step + j*pointCloudChannelCount];
      float y = pointCloudData[step + j*pointCloudChannelCount + 1];
      float z = pointCloudData[step + j*pointCloudChannelCount + 2];
      EXPECT_FLOAT_EQ(minVal, x);
      EXPECT_FLOAT_EQ(minVal, y);
      EXPECT_FLOAT_EQ(minVal, z);
     }
  }

Possible solutions

I'm not sure what is it we're testing:

  • If we're testing the code correctly marks things too close to camera as -inf; then we should move the cube a bit further away from camera so the first face doesn't get clipped
  • If we're testing the object is clipped, then we should look for +inf results

Current workaround

Currently we're workarounding the issue with:

void Ogre2DepthCamera::Render()
{
#ifndef _WIN32
  glEnable(GL_DEPTH_CLAMP);
#endif
   //...
#ifndef _WIN32
  glDisable(GL_DEPTH_CLAMP);
#endif
}

With the following message:

// GL_DEPTH_CLAMP was disabled in later version of ogre2.2
// however our shaders rely on clamped values so enable it for this sensor

Actually after a close inspection: no, ign-rendering's shaders do not rely on GL_DEPTH_CLAMP. It is the tests which rely on it because the tests are submitting wrong inputs.

If sensors behave differently when GL_DEPTH_CLAMP is turned off then one of the following is true:

  1. The sensor was previously picking up stuff too close to camera that should never have been captured at all (e.g. Strange LIDAR returns for various robots osrf/subt#888)
  2. The scene is incorrect and bad data is supplied (model should turn off backface culling, model or sensor should back away a bit) e.g. the tests.

Environment

  • OS Version: Ubuntu 18.04 LTS
  • Source or binary build?
    Source, main, using an up to date ogre-next library

Steps to reproduce

  1. Run INTEGRATION_depth_camera with latest ogre-next
@darksylinc darksylinc added the bug Something isn't working label Sep 5, 2021
@darksylinc
Copy link
Contributor Author

INTEGRATION_thermal_camera suffers from the same issue

@darksylinc
Copy link
Contributor Author

darksylinc commented Sep 5, 2021

INTEGRATION_depth_camera

I can confirm this patch fixes INTEGRATION_depth_camera

diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc
index 211c5ba7..a61bb8da 100644
--- a/test/integration/depth_camera.cc
+++ b/test/integration/depth_camera.cc
@@ -294,7 +294,7 @@ void DepthCameraTest::DepthCameraBoxes(
 
     // Check that for a box really close it returns it is not seen
     ignition::math::Vector3d boxPositionNear(
-        unitBoxSize * 0.5 + nearDist * 0.5, 0.0, 0.0);
+        unitBoxSize * 0.5 + nearDist * 1.0, 0.0, 0.0);
     box->SetLocalPosition(boxPositionNear);
 
     // update and verify we get new data

I analyzed the render with RenderDoc and it seems there is a gap between the cube and the near plane, therefore I tried different values:

  • If we submit nearDist * 1.05 then the test starts failing because it now sees the cube.
  • If we submit nearDist * 1.00 the test passes because the shader sees the cube but decides to discard it
  • If we submit nearDist * 0.91 then the test still passes;
  • If we submit nearDist * 0.90 the test fails as the cube is not rendered at all

INTEGRATION_thermal_camera

I can confirm the following patch fixes INTEGRATION_thermal_camera:

diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc
index dc7144cf..f989ddc6 100644
--- a/test/integration/thermal_camera.cc
+++ b/test/integration/thermal_camera.cc
@@ -226,7 +226,7 @@ void ThermalCameraTest::ThermalCameraBoxes(
     // 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);
+        unitBoxSize * 0.5 + nearDist * 1.05, 0.0, 0.0);
     box->SetLocalPosition(boxPositionNear);
     thermalCamera->Update();
 
@@ -414,7 +414,7 @@ void ThermalCameraTest::ThermalCameraBoxes8Bit(
     // 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);
+        unitBoxSize * 0.5 + nearDist * 1.05, 0.0, 0.0);
     box->SetLocalPosition(boxPositionNear);
     thermalCamera->Update()

@iche033
Copy link
Contributor

iche033 commented Sep 7, 2021

We are trying to simulate the case where objects are too close to a physical depth camera, i.e. in the 'dead zone' (can be up to a meter or more, e.g. a Kinect sensor), which the camera is not able to produce sensible values. In this case, we must return -inf. The color doesn't matter that much as users should see -inf and know that color is also not valid. So the test is set up to test the edge case below.

Untitled presentation

So from the rendering perspective we actually want the camera to see the cube but return -inf. We are probably misusing depth clamping, but with it enabled, we're able to just assume values that are smaller or equal to near clip are in this dead zone so we return -inf. I think another way to fix this could be to use a very small near clip plane distance and manually clip the depth values in our shaders. There could be some precision loss with increased distance between near and far clip planes with this approach, not sure.

Let me know if you have any suggestion on tweaking the code to simulate this case above.

@darksylinc
Copy link
Contributor Author

OK I see 2 issues:

Issue 1: Conflicting goals

  1. You want to detect if an object is so close it would cause real world sensors to return bogus data.
  2. But at the same time you want to filter out those close objects because of mesh/model geometry issues

These two goals are conflicting with each other. Either you return -inf because something is blocking the sensor, or you leave that blocker out so you can see what was behind that blocker.

Issue 2: Detecting things so close, they end up behind the near plane

Such as the photo you are describing.

That is impossible. Depth clamp just happens to solve it. In theory it could be the right solution, but it could also lead to edge cases that need to be handled carefully (i.e. when an object is fully behind the camera). It happens by accident that Ogre's frustum culling manages to handle most of those edge cases but that was more of a happy accident.

Another solution that works would be too have a really small near plane like you suggested, and a fake near plane you use in your post processing shader to turn close values into -inf. That would probably achieve your goal. But at the cost of depth buffer precision since small near clip planes terribly affect depth precision (ogre-next 2.2 is a better fit because it defaults to reverse depth which has much better depth precision than regular depth; but still a small near plane has a deep negative impact)

Still, you are left with solving Issue 1 Conflicting Goals.

@iche033
Copy link
Contributor

iche033 commented Sep 8, 2021

Issue 1: Conflicting goals

ouch, I'll need to revisit #356. If I have to pick one, I would say keeping the current behavior and returning -inf is more important as robots may rely on this value to know if an obstacle is in its path.

As for clipping out certain geometry, the common use case I see is when users place the gpu lidar sensor inside a mesh representing the physical lidar device and they want to see through the mesh.

I think we'll need a way for users to specify a configuration that captures the desired behavior. Currently we let users specify min and max range of lidar (which translates to near and far clip planes). Just brainstorming ideas, we could either use visibiliy mask / flags, or have a second near clip plane for clipping geometry:

camera min near clip

We'll need to think about this a bit more. Unfortunately it won't be done it in time for Fortress. So I'll keep the current behavior and try get the existing PRs merged first.

@darksylinc
Copy link
Contributor Author

darksylinc commented Sep 11, 2021

Just brainstorming ideas, we could either use visibiliy mask / flags, or have a second near clip plane for clipping geometry:

Yes, brainstorming; I also agree with a "2nd" near clip plane:

  1. Real Near Clip plane: Anything behind this is clipped/removed. This setting is basically "my geometry setup is poor, please fix it for me".
  2. Min. Lidar distance: Anything behind this (but larger than real near clip) returns -inf

So:

x < nearClip Removed
nearClip < x < minLidarDist -inf
minLidarDist < x Valid depth value measured by sensor

We can even do slightly more complex stuff like define an AABB instead of a nearClip (i.e. the user wants to get rid of the geometry in front of the sensor due to improper mesh setup; but doesn't want to get rid of the floor and/or ceiling)

Visibiliy mask could also work as you mention but I feel that'd be more user hostile; and needs proper geometry setup (and the problem we're trying to solve is improper geometry setup). Because one small mistake and instead of just masking out the geometry that is close to the sensor, you end up masking out the entire vehicle.

Anyway 2 values for min distance would fix issue 1, as we no longer have contradicting goals. We'd still have the problem of what happens when the sensor is "inside" the cube; but that's harder to fix because we don't know intended usage (is the cube hollow? is it full? what about back face culling? should the cube not have any face culling?).

Issue 2 is easier to understand with a video, this is what happens when you get inside a cube with and without backface culling:

2021-09-11.12-42-47.mkv.mp4

INTEGRATION_depth_camera fails when depth clamp is disabled because we get inside the cube (and backface culling is enabled).

@darksylinc
Copy link
Contributor Author

Just to be clear: The thing about issue 2, is that we first need to determine what it means "to be inside the cube" (or alternatively what it means to be able to walk through objects/walls like a ghost) and once we define that; we can discuss how we deal with it.

@iche033
Copy link
Contributor

iche033 commented Sep 14, 2021

ok good to know that two near clipping plane approach is feasible. I see the use case for the AABB approach. That maybe a little complex for users to specify, e.g. min + max vectors vs 1 near clip plane value. I'll keep this in mind in case we run into this use case.

we first need to determine what it means "to be inside the cube"

assuming we go with the nearClip and minLidarDist approach, we can say that the sensor is inside the cube if the true nearClip is also inside the cube. We can keep backface culling enabled - as that 's the current behavior, which means the sensor will see open space (if there's nothing behind the cube).

As for the setup shown in the image in #395 (comment), since the true nearClip is outside the cube, we can say the sensor is outside the cube.

INTEGRATION_depth_camera fails when depth clamp is disabled because we get inside the cube (and backface culling is enabled).

I think to fix this particular case in the test: , we will just need to change the setup so that:

  • the current near clip plane becomes min lidar dist
  • add a true near clip value that places the plane between the camera pos and closest face of the cube (the camera pos is currently located at [0 0 0] and the closest face is at [0.075 0 0]).

@darksylinc
Copy link
Contributor Author

I see the use case for the AABB approach. That maybe a little complex for users to specify, e.g. min + max vectors vs 1 near clip plane value. I'll keep this in mind in case we run into this use case.

I was thinking of specifying half extents (i.e. 3 float values, one for each axis) centered at the camera. It's less flexible but more intuitive and easier to implement too.

Anyway we can expose different modes (radius, half extent, min+max aabb) if needed

As for the setup shown in the image in #395 (comment), since the true nearClip is outside the cube, we can say the sensor is outside the cube.

Ah cool

@chapulina chapulina added the help wanted Extra attention is needed label Oct 4, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working help wanted Extra attention is needed
Projects
None yet
Development

No branches or pull requests

3 participants