Skip to content

Fortress: Light gizmo (visual) is rendered in lidar #969

Open
@peci1

Description

Environment

  • OS Version: Ubuntu 20.04
  • Source or binary build? Binary 6.16
  • If this is a GUI or sensor rendering bug, describe your GPU and rendering system. Otherwise delete this section.
    • Rendering plugin: ogre, ogre2 (both affected)
      • Sensor rendering error.
      • GUI rendering error.
    • EGL headless mode:
      • Running in EGL headless mode
    • Generally, mention all circumstances that might affect rendering capabilities:
      • running on a dual GPU machine (integrated GPU + discrete GPU)
      • running on a multi-GPU machine (it has multiple discrete GPUs)
      • running on real hardware
      • running in virtual machine
      • running in Docker/Singularity
      • running remotely (e.g. via SSH)
      • running in a cloud
      • using VirtualGL, XVFB, Xdummy, XVNC or other indirect rendering utilities
      • GPU is concurrently used for other tasks
        • desktop acceleration
        • video decoding (i.e. a playing Youtube video)
        • video encoding
        • CUDA/ROCm computations (Tensorflow, Torch, Caffe running)
        • multiple simulators running at the same time
      • other...
    • Rendering system info:
      • On Linux, provide the outputs of the following commands:
$ LANG=C lspci -nn | grep VGA  # might require installing pciutils
06:00.0 VGA compatible controller [0300]: Advanced Micro Devices, Inc. [AMD/ATI] Renoir [1002:1636] (rev d1)
$           echo "$DISPLAY"
:0
$           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 Radeon Graphics (radeonsi, renoir, LLVM 15.0.7, DRM 3.57, 6.7.5-060705-generic)
OpenGL core profile version string: 4.6 (Core Profile) Mesa 24.0.1 - 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 24.0.1 - 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 24.0.1 - kisak-mesa PPA
OpenGL ES profile shading language version string: OpenGL ES GLSL ES 3.20
$           ps aux | grep Xorg
peci1       4438  1.0  0.3 1602564 99212 tty2    Sl+  úno22  73:58 /usr/lib/xorg/Xorg vt2 -displayfd 3 -auth /run/user/1000/gdm/Xauthority -background none -noreset -keeptty -verbose 3
peci1     670952  0.0  0.0  11600  2544 pts/5    S+   17:08   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.13
X Protocol Version 11, Revision 0
Build Operating System: linux Ubuntu
Current Operating System: Linux cras-17 6.7.5-060705-generic #202402161836 SMP PREEMPT_DYNAMIC Fri Feb 16 19:10:40 UTC 2024 x86_64
Kernel command line: BOOT_IMAGE=/boot/vmlinuz-6.7.5-060705-generic root=UUID=c8df4187-97f0-4be7-b095-39958ee965df ro quiet splash vt.handoff=7
Build Date: 29 January 2024  12:44:21PM
xorg-server 2:1.20.13-1ubuntu1~20.04.15 (For technical support please see http://www.ubuntu.com/support) 
Current version of pixman: 0.38.4
	Before reporting problems, check http://wiki.x.org
	to make sure that you have the latest version.
  • Please, attach the ogre.log or ogre2.log file from ~/.gz/rendering

Description

  • Expected behavior: Light gizmos are not visible in lidar.
  • Actual behavior: A light with <visualize>true</visualize> causes the gizmo to be captured by gpu lidar.

Steps to reproduce

  1. Add a light to the simulation and a GPU lidar.
  2. Watch the lidar points.
  3. Turn off the light gizmo using Component inspector.
  4. The gizmo disappears from the lidar points.

MWE:

<sdf version='1.9'>
  <world name='example'>
    <physics name='4ms' type='dart'>
      <max_step_size>0.0040000000000000001</max_step_size>
      <real_time_factor>1</real_time_factor>
      <real_time_update_rate>1000</real_time_update_rate>
    </physics>
    <scene>
      <ambient>0.2 0.2 0.2 1</ambient>
      <background>0.8 0.8 0.8 1</background>
      <shadows>true</shadows>
    </scene>
    <gravity>0 0 -9.8</gravity>
    <magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
    <atmosphere type='adiabatic'/>

    <plugin filename="ignition-gazebo-sensors-system" name="ignition::gazebo::systems::Sensors">
      <render_engine>ogre2</render_engine>
    </plugin>
    <plugin filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics"/>
    <plugin filename="ignition-gazebo-user-commands-system" name="ignition::gazebo::systems::UserCommands"/>
    <plugin filename="ignition-gazebo-scene-broadcaster-system" name="ignition::gazebo::systems::SceneBroadcaster"/>

    <include><uri>https://fuel.gazebosim.org/1.0/OpenRobotics/models/Ground Plane</uri></include>

    <model name='X1'>
      <link name='top_box'>
        <inertial>
          <mass>2</mass>
          <inertia>
            <ixx>0.01755</ixx>
            <iyy>0.0070666699999999997</iyy>
            <izz>0.013816699999999999</izz>
          </inertia>
          <pose>0 0 0 0 -0 0</pose>
        </inertial>
        <collision name='top_box_collision'>
          <geometry>
            <box>
              <size>0.1 0.11 0.18</size>
            </box>
          </geometry>
        </collision>
        <visual name='top_box_visual'>
          <geometry>
            <box>
              <size>0.1 0.11 0.18</size>
            </box>
          </geometry>
        </visual>
        <light name='light_up' type='spot'>
          <pose>0 -0.07 0.045 3.14159 -0 3.14159</pose>
          <cast_shadows>false</cast_shadows>
          <intensity>1</intensity>
          <direction>0 0 -1</direction>
          <diffuse>0.8 0.8 0.5 1</diffuse>
          <specular>0.8 0.8 0.5 1</specular>
          <visualize>true</visualize>
          <attenuation>
            <range>60</range>
            <linear>0</linear>
            <constant>0.10000000000000001</constant>
            <quadratic>0.0025000000000000001</quadratic>
          </attenuation>
          <spot>
            <inner_angle>1.0471999999999999</inner_angle>
            <outer_angle>1.5708</outer_angle>
            <falloff>1</falloff>
          </spot>
        </light>
      </link>
      <link name='laser'>
        <pose>0 0 0.12 0 -0 0</pose>
        <inertial>
          <mass>0.5</mass>
          <inertia>
            <ixx>0.00046162500000000001</ixx>
            <iyy>0.00046162500000000001</iyy>
            <izz>0.00047306300000000002</izz>
          </inertia>
        </inertial>
        <collision name='laser_collision'>
          <geometry>
            <cylinder>
              <length>0.073499999999999996</length>
              <radius>0.043499999999999997</radius>
            </cylinder>
          </geometry>
        </collision>
        <visual name='laser_visual'>
          <geometry>
            <cylinder>
              <length>0.073499999999999996</length>
              <radius>0.043499999999999997</radius>
            </cylinder>
          </geometry>
        </visual>
        <sensor name='laser' type='gpu_lidar'>
          <update_rate>10</update_rate>
          <lidar>
            <scan>
              <horizontal>
                <samples>1024</samples>
                <resolution>1</resolution>
                <min_angle>-3.1459000000000001</min_angle>
                <max_angle>3.1459000000000001</max_angle>
              </horizontal>
              <vertical>
                <samples>128</samples>
                <min_angle>-0.78539800000000004</min_angle>
                <max_angle>0.78539800000000004</max_angle>
                <resolution>1</resolution>
              </vertical>
            </scan>
            <range>
              <min>0.10000000000000001</min>
              <max>50</max>
              <resolution>0.01</resolution>
            </range>
            <noise>
              <type>gaussian</type>
              <mean>0</mean>
              <stddev>0.01</stddev>
            </noise>
          </lidar>
        </sensor>
      </link>
      <joint name='laser_j' type='fixed'>
        <child>laser</child>
        <parent>top_box</parent>
        <axis>
          <xyz>0 0 1</xyz>
        </axis>
      </joint>
      <pose>-0 -0 0.1145 0 0 -0</pose>
      <static>false</static>
      <self_collide>false</self_collide>
    </model>
  </world>
</sdf>

To reproduce, run rosrun ros_ign_bridge parameter_bridge '/world/example/model/X1/link/laser/sensor/laser/scan/points@sensor_msgs/PointCloud2[ignition.msgs.PointCloudPacked' and open up rviz with rviz -f X1/laser/laser and add the PointCloud2 topic.

Output

rviz_screenshot_2024_02_27-17_07_05

2024-02-27T17:15:25 766369296

Activity

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    • Status

      To do

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions