gz-rendering icon indicating copy to clipboard operation
gz-rendering copied to clipboard

OGRE2: Meshes with odd number of negative scale elements are rendered with inverted normals

Open peci1 opened this issue 3 years ago • 2 comments

Environment

  • OS Version: Ubuntu 18.04
  • Source or binary build: Binary, 4.6.0

Description

  • Expected behavior: If a visual mesh has <scale>-1 1 1</scale> it should be rendered just as a mirrored version of the scale-less version.
  • Actual behavior: Backface culling culls the wrong faces from the scaled mesh, making it partly transparent. This hints at inverted normals. With OGRE1, this is okay and the scaled meshes are solid. With OGRE2, the scaled meshes behave as explained.

Steps to reproduce

  1. Run the attached SDF world in Ignition Gazebo 4 with OGRE 2 renderer.
  2. Open an Image display to verify this issue affects both GUI camera and sensors.
  3. Examine the scene. Visuals 1 and 4 are rendered correctly (you can't see the miniature cube inside them), while visuals 2, 3 and 5 render half-transparent showing the little cubes that should be hidden inside them.

Here's the test SDF:

test.sdf:

<?xml version="1.0" ?>
<sdf version="1.6">
    <world name="example">
        <plugin
                filename="ignition-gazebo-sensors-system"
                name="ignition::gazebo::systems::Sensors">
            <render_engine>ogre2</render_engine>
        </plugin>
        <plugin
                filename="ignition-gazebo-scene-broadcaster-system"
                name="ignition::gazebo::systems::SceneBroadcaster">
        </plugin>

        <model name="scale_test">
            <static>true</static>
            <link name="base_link">
                <visual name="base_link_visual1">
                    <pose>0 0 1 0 0 0</pose>
                    <geometry>
                        <mesh>
                            <uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Number1/tip/files/meshes/number.dae</uri>
                            <scale>1 1 1</scale>
                        </mesh>
                    </geometry>
                </visual>
                <visual name="base_link_visual1_box">
                    <pose>0 0 1 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.05 0.05 0.05</size>
                        </box>
                        <material>
                            <ambient>1 0 0 1</ambient>
                            <diffuse>0.8 0.8 0.8 1</diffuse>
                            <specular>0.8 0.8 0.8 1</specular>
                        </material>
                    </geometry>
                </visual>
                <visual name="base_link_visual2">
                    <pose>0 3 1 0 0 0</pose>
                    <geometry>
                        <mesh>
                            <uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Number1/tip/files/meshes/number.dae</uri>
                            <scale>-1 1 1</scale>
                        </mesh>
                    </geometry>
                </visual>
                <visual name="base_link_visual2_box">
                    <pose>0 3 1 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.05 0.05 0.05</size>
                        </box>
                        <material>
                            <ambient>1 0 0 1</ambient>
                            <diffuse>0.8 0.8 0.8 1</diffuse>
                            <specular>0.8 0.8 0.8 1</specular>
                        </material>
                    </geometry>
                </visual>
                <visual name="base_link_visual3">
                    <pose>3 0 1 0 0 0</pose>
                    <geometry>
                        <mesh>
                            <uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Number1/tip/files/meshes/number.dae</uri>
                            <scale>1 -1 1</scale>
                        </mesh>
                    </geometry>
                </visual>
                <visual name="base_link_visual3_box">
                    <pose>3 0 1 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.05 0.05 0.05</size>
                        </box>
                        <material>
                            <ambient>1 0 0 1</ambient>
                            <diffuse>0.8 0.8 0.8 1</diffuse>
                            <specular>0.8 0.8 0.8 1</specular>
                        </material>
                    </geometry>
                </visual>
                <visual name="base_link_visual4">
                    <pose>3 3 1 0 0 0</pose>
                    <geometry>
                        <mesh>
                            <uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Number1/tip/files/meshes/number.dae</uri>
                            <scale>-1 -1 1</scale>
                        </mesh>
                    </geometry>
                </visual>
                <visual name="base_link_visual4_box">
                    <pose>3 3 1 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.05 0.05 0.05</size>
                        </box>
                        <material>
                            <ambient>1 0 0 1</ambient>
                            <diffuse>0.8 0.8 0.8 1</diffuse>
                            <specular>0.8 0.8 0.8 1</specular>
                        </material>
                    </geometry>
                </visual>
                <visual name="base_link_visual5">
                    <pose>3 6 1 0 0 0</pose>
                    <geometry>
                        <mesh>
                            <uri>https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Number1/tip/files/meshes/number.dae</uri>
                            <scale>-1 -1 -1</scale>
                        </mesh>
                    </geometry>
                </visual>
                <visual name="base_link_visual5_box">
                    <pose>3 6 1 0 0 0</pose>
                    <geometry>
                        <box>
                            <size>0.05 0.05 0.05</size>
                        </box>
                        <material>
                            <ambient>1 0 0 1</ambient>
                            <diffuse>0.8 0.8 0.8 1</diffuse>
                            <specular>0.8 0.8 0.8 1</specular>
                        </material>
                    </geometry>
                </visual>

                <sensor name="camera" type="camera">
                    <update_rate>6.0</update_rate>
                    <pose>-5 3 5 0 0.5 0</pose>
                    <camera name="camera">
                        <horizontal_fov>1</horizontal_fov>
                        <image>
                                <width>640</width>
                                <height>480</height>
                                <format>R8G8B8</format>
                        </image>
                        <clip>
                                <near>0.02</near>
                                <far>300</far>
                        </clip>
                    </camera>
                </sensor>
            </link>
        </model>
    </world>
</sdf>

Output

This happens with all kinds of meshes, simple or complex, Collada or STL. Whenever there is an odd number of negative scale elements (so 1 or 3), the wrong faces are culled. A colleague hinted that this might have something to do with (non-)right-handedness of the scaled coordinate system.

The SDF spec doesn't mention anything about this being a desired behavior in the <scale> docs.

Snímek z 2021-03-08 22-13-15

peci1 avatar Mar 08 '21 21:03 peci1