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

OGRE2: Camera sensor clipping stops working when model is rotated #128

Open
2 tasks done
peci1 opened this issue May 1, 2021 · 6 comments
Open
2 tasks done

OGRE2: Camera sensor clipping stops working when model is rotated #128

peci1 opened this issue May 1, 2021 · 6 comments
Labels
bug Something isn't working help wanted Extra attention is needed

Comments

@peci1
Copy link
Contributor

peci1 commented May 1, 2021

Environment

  • OS Version: Ubuntu 18.04
  • Source or binary build? binary 4.1.0
  • If this is a GUI or sensor rendering bug, describe your GPU and rendering system. Otherwise delete this section.
    • Rendering plugin: ogre2
      • Sensor rendering error.
    • Generally, mention all circumstances that might affect rendering capabilities:
      • running on real hardware
    • Rendering system info:
$ LANG=C glxinfo -B | grep -i '\(direct rendering\|opengl\|profile\)'  # might require installing mesa-utils package
direct rendering: Yes
    Preferred profile: core (0x1)
    Max core profile version: 4.6
    Max compat profile version: 4.6
    Max GLES1 profile version: 1.1
    Max GLES[23] profile version: 3.2
OpenGL vendor string: AMD
OpenGL renderer string: AMD RENOIR (DRM 3.40.0, 5.11.15-051115-generic, LLVM 12.0.0)
OpenGL core profile version string: 4.6 (Core Profile) Mesa 21.0.3 - kisak-mesa PPA
OpenGL core profile shading language version string: 4.60
OpenGL core profile context flags: (none)
OpenGL core profile profile mask: core profile
OpenGL version string: 4.6 (Compatibility Profile) Mesa 21.0.3 - kisak-mesa PPA
OpenGL shading language version string: 4.60
OpenGL context flags: (none)
OpenGL profile mask: compatibility profile
OpenGL ES profile version string: OpenGL ES 3.2 Mesa 21.0.3 - kisak-mesa PPA
OpenGL ES profile shading language version string: OpenGL ES GLSL ES 3.20  
$           ps aux | grep Xorg
peci1     2932  2.9  0.3 2267408 113700 tty2   Sl+  dub27  92:55 /usr/lib/xorg/Xorg vt2 -displayfd 3 -auth /run/user/1000/gdm/Xauthority -background none -noreset -keeptty -verbose 3
peci1    16226  0.0  0.0  15672  1024 pts/1    S+   22:53   0:00 grep --color=auto Xorg
$           sudo env LANG=C X -version  # if you don't have root access, try to tell the version of Xorg e.g. via package manager
X.Org X Server 1.20.8
X Protocol Version 11, Revision 0 
Build Operating System: Linux 4.15.0-140-generic x86_64 Ubuntu
Current Operating System: Linux cras-17 5.11.15-051115-generic #202104161034 SMP Fri Apr 16 10:40:30 UTC 2021   x86_64
Kernel command line: BOOT_IMAGE=/boot/vmlinuz-5.11.15-051115-generic root=UUID=d982512a-7987-4852-992c-9aeeddc50c46 ro amd_iommu=on
Build Date: 08 April 2021  01:40:27PM
xorg-server-hwe-18.04 2:1.20.8-2ubuntu2.2~18.04.5 (For technical support please see http://www.ubuntu.com/support) 
Current version of pixman: 0.34.0
Before reporting problems, check http://wiki.x.org
to make sure that you have the latest version.

Description

  • Expected behavior: Near clip distance of a camera means that all objects that are closer to the camera than this distance are not rendered.
  • Actual behavior: This holds only when the model is aligned with world axes. When the robot is rotated, the clipped objects appear in the camera view.

Steps to reproduce

  1. LANG=C ign gazebo -v4 occlusion.sdf
  2. display camera image
  3. it should be all grey
  4. use transform control or any other means to rotate the model
  5. when the model is rotated by roughly 10 degrees and more, the sphere appears in the camera view

This behavior is wrong because the transform between the sensor and the sphere is static. That should apply consistent behavior no matter where the model is located (except lighting).

The scene in the example is as follows: camera is in the origin, sphere with 0.1 radius is located at X axis 0.25 forward. So the sphere occupies X axis from 0.15 to 0.35. Near clip distance is set to 0.4, so the sphere should not be rendered.

OGRE1 handles this case correctly.

This bug manifests not only with simple shapes, but also with meshes. We've faced it with practically all of our SubT models when preparing them. A simple to test one is Marmotte camera_0 (osrf/subt#842).

In the example SDF, setting camera near clip distance to anything higher than 0.35 triggers this bug.

This happens with "camera" and "thermal" type sensors. Types "rgbd" (both color and depth) and "depth" are not affected. The fact that the color camera from "rgbd" sensor is not affected might point to a possible direction of research for this bug...

Output

Aligned with axes:

Snímek obrazovky pořízený 2021-05-01 23-18-22

Rotated:

Snímek obrazovky pořízený 2021-05-01 23-18-48

Minimum Buggy Example

occlusion.sdf:

<?xml version="1.0" ?>
<sdf version="1.6">
    <world name="test_occlusion">
        <scene>
            <ambient>0.5 0.5 0.5 1.0</ambient>
        </scene>
        <plugin filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics">
            <engine>
                <filename>ignition-physics3-tpe-plugin</filename>
            </engine>
        </plugin>
        <plugin filename="libignition-gazebo-sensors-system.so"
                name="ignition::gazebo::systems::Sensors">
            <render_engine>ogre2</render_engine>
        </plugin>
        <plugin filename="libignition-gazebo-user-commands-system.so"
                name="ignition::gazebo::systems::UserCommands">
        </plugin>
        <plugin filename="libignition-gazebo-scene-broadcaster-system.so"
                name="ignition::gazebo::systems::SceneBroadcaster">
        </plugin>

        <model name="occlusion">
            <static>1</static>
            <link name='base_link'>
                <visual name="test">
                    <pose frame="">0.25 0 0 0 0 0</pose>
                    <geometry>
                        <sphere>
                            <radius>0.1</radius>
                        </sphere>
                    </geometry>
                </visual>
                <sensor name="camera" type="camera">
                    <camera name="camera">
                        <horizontal_fov>1.3</horizontal_fov>
                        <image>
                            <width>960</width>
                            <height>600</height>
                            <format>R8G8B8</format>
                        </image>
                        <clip>
                            <near>0.4</near>
                            <far>300</far>
                        </clip>
                    </camera>
                    <update_rate>6</update_rate>
                </sensor>
            </link>
        </model>

    </world>
</sdf>
@peci1 peci1 added the bug Something isn't working label May 1, 2021
@mjcarroll mjcarroll self-assigned this May 3, 2021
@iche033
Copy link
Contributor

iche033 commented May 3, 2021

I think the reason is that for rgbd cameras, we are manually clipping the view ourselves based on depth values in fragment shader and the result is going to be more accurate. While for camera and thermal sensors, we rely on ogre to do the clipping. My guess is that it's probably doing some sort of frustum and object's axis-aligned bounding box intersection check to cull objects in the camera view. So when the model is rotated, the camera frustum is also rotated but not the sphere's bounding box's orientation (it still remains axis-aligned in world space) which causes the frustum and the bounding box to intersect and so the sphere visual becomes visible.

@peci1
Copy link
Contributor Author

peci1 commented May 4, 2021

So the solution would be to do the clipping manually in all cases? Or should it be solved in OGRE? Maybe both, with the manual clipping being a transitional feature until OGRE gets fixed?

@iche033
Copy link
Contributor

iche033 commented May 5, 2021

I think we maybe able to fix it for the thermal camera as it's using its own custom shaders already. For RGB camera we would probably need to add an extra shader pass for manual clipping.

I don't know if this is something that'll be fixed in OGRE 2 though. It could be designed this way for more faster culling of objects in the view and accuracy is not a priority here.

@peci1
Copy link
Contributor Author

peci1 commented May 5, 2021

Okay. Fixing it in ign-rendering would be the faster option. However, my shader programming skills are close to zero, so I can't help sending a PR...

@chapulina chapulina added help wanted Extra attention is needed bug Something isn't working and removed bug Something isn't working labels May 10, 2021
@peci1
Copy link
Contributor Author

peci1 commented Jun 2, 2021

GPU lidar is also affected and it is pretty bad! Try with CTU_CRAS_NORLAB_SPOT_SENSOR_CONFIG_1 in SubT simulator, or MARV.

Robot parallel with world axes:

spot_ok

Robot about 30° to world:

spot_half_bad

Robot 45° to world:

spot_all_bad

Yellow points mark those closer than 0.2 m from the sensor.

Sensor definition:

    <sensor name="laser" type="gpu_lidar">
        <pose>0 0 0.035925 0 -0 0</pose>
        <update_rate>10</update_rate>
        <visualize>0</visualize>
        <always_on>1</always_on>
        <lidar>
          <scan>
            <horizontal>
              <samples>2048</samples>
              <resolution>1</resolution>
              <min_angle>-3.1459</min_angle>
              <max_angle>3.1459</max_angle>
            </horizontal>
            <vertical>
              <samples>128</samples>
              <resolution>1</resolution>
              <min_angle>-0.785398</min_angle>
              <max_angle>0.785398</max_angle>
            </vertical>
          </scan>
          <range>
            <min>0.1</min>
            <max>50</max>
            <resolution>0.01</resolution>
          </range>
          <noise>
            <type>gaussian</type>
            <mean>0</mean>
            <stddev>0.01</stddev>
          </noise>
        </lidar>
      </sensor>

@darksylinc
Copy link
Contributor

I don't know if this is something that'll be fixed in OGRE 2 though. It could be designed this way for more faster culling of objects in the view and accuracy is not a priority here.

That is not an explanation though 😞 . If an object is fully visible at 45° but not at 0° because our culling calculations decided it so, that's a bug. We are not sacrificing accuracy THAT much.

But I don't think that is what's happening.

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

5 participants