Weird Flickering when <cast_shadow> is set to true

Hi, I am experimenting with Gazebo SDF world files.
I noticed that when I turn on the <cast_shadow> property of a directional light I added to the world, the sky starts “flickering” with weird horizontal lines.

Here is a screenshot of the simulation and the SDF file:

<?xml version="1.0"?>
<sdf version="1.8">
  <world name="test">
    <scene>
      <ambient>1.0 1.0 1.0 1.0</ambient>
      <background>0.5 0.5 0.5 1.0</background>
      <sky>
        <time>10.0</time>
        <sunrise>6.0</sunrise>
        <sunset>18.0</sunset>
      </sky>
      <shadows>True</shadows>
      <grid>True</grid>
      <origin_visual>True</origin_visual>
    </scene>
    <light name="Sun" type="directional">
      <diffuse>0.7 0.7 0.7 0.0</diffuse>
      <specular>1.0 1.0 1.0 0.0</specular>
      <direction>-1.0 -1.0 -1.0</direction>
      <cast_shadows>True</cast_shadows>
    </light>
    <model name="ground">
      <static>True</static>
      <link name="ground">
        <pose>0 0 -0.25 0.0 0.0 0.0</pose>
        <inertial>
          <mass>1.0</mass>
          <inertia>
            <ixx>1.0</ixx>
            <iyy>1.0</iyy>
            <izz>1.0</izz>
            <ixy>0.0</ixy>
            <ixz>0.0</ixz>
            <iyz>0.0</iyz>
          </inertia>
        </inertial>
        <collision name="visual">
          <geometry>
            <box>
              <size>100.0 100.0 0.5</size>
            </box>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <box>
              <size>100.0 100.0 0.5</size>
            </box>
          </geometry>
          <material>
            <ambient>0.5 0.5 0.5 1.0</ambient>
            <diffuse>0.5 0.5 0.5 1.0</diffuse>
            <specular>0 0 0 0</specular>
            <emissive>0 0 0 1</emissive>
          </material>
        </visual>
      </link>
    </model>
    <model name="box">
      <static>True</static>
      <link name="box">
        <pose>0.0 0.0 2.0 0.0 0.0 0.0</pose>
        <inertial>
          <mass>1.0</mass>
          <inertia>
            <ixx>1.0</ixx>
            <iyy>1.0</iyy>
            <izz>1.0</izz>
            <ixy>0.0</ixy>
            <ixz>0.0</ixz>
            <iyz>0.0</iyz>
          </inertia>
        </inertial>
        <collision name="visual">
          <geometry>
            <box>
              <size>1.0 1.0 1.0</size>
            </box>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <box>
              <size>1.0 1.0 1.0</size>
            </box>
          </geometry>
          <material>
            <ambient>0.0 0.0 1.0 1.0</ambient>
            <diffuse>0.0 0.0 1.0 1.0</diffuse>
            <specular>0 0 0 0</specular>
            <emissive>0 0 0 1</emissive>
          </material>
        </visual>
      </link>
    </model>
    <model name="cylinder">
      <static>True</static>
      <link name="cylinder">
        <pose>2.0 1.0 2.0 0.0 0.0 0.0</pose>
        <inertial>
          <mass>1.0</mass>
          <inertia>
            <ixx>1.0</ixx>
            <iyy>1.0</iyy>
            <izz>1.0</izz>
            <ixy>0.0</ixy>
            <ixz>0.0</ixz>
            <iyz>0.0</iyz>
          </inertia>
        </inertial>
        <collision name="visual">
          <geometry>
            <cylinder>
              <radius>1.0</radius>
              <length>1.0</length>
            </cylinder>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <cylinder>
              <radius>1.0</radius>
              <length>1.0</length>
            </cylinder>
          </geometry>
          <material>
            <ambient>0.0 1.0 0.0 1.0</ambient>
            <diffuse>0.0 1.0 0.0 1.0</diffuse>
            <specular>0 0 0 0</specular>
            <emissive>0 0 0 1</emissive>
          </material>
        </visual>
      </link>
    </model>
    <model name="sphere">
      <static>True</static>
      <link name="sphere">
        <pose>0.1 -5.0 2.0 0.0 0.0 0.0</pose>
        <inertial>
          <mass>1.0</mass>
          <inertia>
            <ixx>1.0</ixx>
            <iyy>1.0</iyy>
            <izz>1.0</izz>
            <ixy>0.0</ixy>
            <ixz>0.0</ixz>
            <iyz>0.0</iyz>
          </inertia>
        </inertial>
        <collision name="visual">
          <geometry>
            <sphere>
              <radius>1.0</radius>
            </sphere>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <sphere>
              <radius>1.0</radius>
            </sphere>
          </geometry>
          <material>
            <ambient>1.0 0.0 0.0 1.0</ambient>
            <diffuse>1.0 0.0 0.0 1.0</diffuse>
            <specular>0 0 0 0</specular>
            <emissive>0 0 0 1</emissive>
          </material>
        </visual>
      </link>
    </model>
  </world>
</sdf>

This might be related to a recently opened issue: https://github.com/gazebosim/gz-sim/issues/2267. Can you take a look and add a comment there if it’s the same problem? It would be good to get your system information as an additional data point.

1 Like